diff options
710 files changed, 200978 insertions, 0 deletions
diff --git a/Makefile b/Makefile new file mode 100644 index 0000000..00db7a9 --- /dev/null +++ b/Makefile @@ -0,0 +1,169 @@ +# dumb dumb dumb makefile +# Project name +PROJECT=maple + +# STM Library prefix +STM_SRC = stm32lib/src +STM_CONF = stm32conf/flash.conf + +# ARM/GNU toolchain parameters +CC = arm-none-eabi-gcc +CPP = arm-none-eabi-g++ +LD = arm-none-eabi-ld -v +AR = arm-none-eabi-ar +AS = arm-none-eabi-as +CP = arm-none-eabi-objcopy +OD = arm-none-eabi-objdump + +BUILD_PATH = build +LIB_PATH = lib +COMM_PATH = comm + +OUTDIRS = $(BUILD_PATH)/src/$(STM_SRC) \ + $(BUILD_PATH)/src/$(LIB_PATH)\ + $(BUILD_PATH)/src/comm \ + $(BUILD_PATH)/src/wiring \ + $(BUILD_PATH)/src/wiring/comm + + +INCLUDES = -Isrc/stm32lib/inc \ + -Isrc/$(LIB_PATH) \ + -Isrc/$(COMM_PATH) \ + -Isrc/ \ + -Isrc/wiring \ + -Isrc/wiring/comm + +CFLAGS = -I./ $(INCLUDES) -c \ + -Os\ + -g -mcpu=cortex-m3 -mthumb -march=armv7-m -nostdlib \ + -ffunction-sections -fdata-sections -Wl,--gc-sections + + +CPPFLAGS = -fno-rtti -fno-exceptions -Wall + +LFLAGS = -Tstm32conf/lanchon-stm32.ld -L stm32conf/lanchon-stm32 \ + -mcpu=cortex-m3 -mthumb -Xlinker \ + --gc-sections --print-gc-sections --march=armv7-m -Wall + +CPFLAGS = -v -Obinary +ODFLAGS = -S + +# main ource file +MAIN=main.c + +STM32SRCS = $(STM_SRC)/stm32f10x_flash.c \ + $(STM_SRC)/stm32f10x_nvic.c \ + $(STM_SRC)/stm32f10x_rcc.c + +CSRC = lib/systick.c \ + lib/timers.c \ + lib/adc.c \ + lib/syscalls.c \ + lib/stm32f10x_it.c \ + lib/exti.c \ + lib/gpio.c \ + lib/usart.c \ + wiring/wiring.c \ + wiring/wiring_shift.c \ + wiring/wiring_analog.c \ + wiring/time.c \ + wiring/pwm.c \ + wiring/ext_interrupts.c \ + wiring/wiring_digital.c + +CSRC += $(STM32SRCS) + +CPPSRC = lib/util.cpp \ + wiring/math.cpp \ + wiring/Print.cpp \ + wiring/comm/Serial.cpp \ + main.cpp + +# i really have no idea what i'm doing +meep += $(CSRC) +moop = $(patsubst %, src/%, $(meep)) +beep = $(CPPSRC) +boop = $(patsubst %, src/%, $(beep)) + +# English +MSG_ERRORS_NONE = Errors: none +MSG_BEGIN = -------- begin -------- +MSG_ETAGS = Created TAGS File +MSG_END = -------- end -------- +MSG_SIZE = Program Image Size: +MSG_LINKING = Linking: +MSG_COMPILING = Compiling C: +MSG_ASSEMBLING = Assembling: +MSG_CLEANING = Cleaning project: +MSG_FLASH = Creating load file for Flash: + +# output directories +all: $(BUILD_PATH)/main.bin + +$(BUILD_PATH): + mkdir -p build + +_COBJ = $(moop:.c=.o) +_CPPOBJ = $(boop:.cpp=.o) +COBJ = $(patsubst %, $(BUILD_PATH)/%,$(_COBJ)) +CPPOBJ = $(patsubst %, $(BUILD_PATH)/%,$(_CPPOBJ)) + + +.PHONY: test install run cscope clean + +test: $(CSRC_) + @echo help + @echo $(moop) + @echo done + +$(OUTDIRS): + @echo Making directory $@ + mkdir -p $@ + @echo + +# actual build rules +$(COBJ) : $(BUILD_PATH)/%.o : %.c + @echo $(MSG_COMPILING) $< + $(CC) $(CFLAGS) -c $< -o $@ + @echo + +$(CPPOBJ) : $(BUILD_PATH)/%.o : %.cpp + @echo $(MSG_COMPILING) $< + $(CPP) $(CFLAGS) $(CPPFLAGS) -c $< -o $@ + @echo + + +# targets +$(BUILD_PATH)/$(PROJECT).out: $(OUTDIRS) $(COBJ) $(CPPOBJ) + @echo Linking + @echo CPP OBJ: $(CPPOBJ) + @echo + @echo C OBJ: $(COBJ) + @echo + $(CC) $(LFLAGS) -o $(BUILD_PATH)/$(PROJECT).out $(COBJ) $(CPPOBJ) + @echo + +$(BUILD_PATH)/main.bin: $(BUILD_PATH)/$(PROJECT).out + $(CP) $(CPFLAGS) $(BUILD_PATH)/$(PROJECT).out $(BUILD_PATH)/main.bin + $(OD) $(ODFLAGS) $(BUILD_PATH)/$(PROJECT).out > $(BUILD_PATH)/$(PROJECT).d + @echo + find $(BUILD_PATH) -iname *.o | xargs arm-none-eabi-size -t + @echo + @echo "Final Size:" + arm-none-eabi-size $< + + +install: $(BUILD_PATH)/main.bin + openocd -f stm32conf/flash.cfg + +run: $(BUILD_PATH)/main.bin + openocd -f stm32conf/run.cfg + +cscope: + rm -rf *.cscope + find . -iname "*.[hcs]" | grep -v examples | xargs cscope -R -b + +clean: + rm -f *.hex *.o + rm -rf build/* + diff --git a/README.txt b/README.txt new file mode 100644 index 0000000..802aa24 --- /dev/null +++ b/README.txt @@ -0,0 +1,91 @@ +/* Temporary file for notes to myself. */ +/* Known Errors: + * Schematic: PB9 is mislabeled as TIM3_CH4: should be TIM4_CH4 + * Silkscreen: D2 is incorrectly marked as not having PWM capability. It does. + * Silkscreen: D10 is incorrectly marked as having PWM capability. It does not. + * + * D15 is mapped to pin number 38. This is to retain compatiblity with the + * Arduino API, where digitalWrite() on pins 14-19 map to analog A0-A5 + * + * Fix serial/timer + * Add external itnerrupts + * Redo serial api + * + * Order some shields + * buy some toner + * LARW BOOK + * + * + * wtf is smba/smbal? + * serial.print + * + * 5v tolerance + * + * TODO: + * Using OSC32_IN/OSC32_OUT pins as GPIO ports PC14/PC15 152/995 + * */ + +/* 51 GPIOs in general + * + * Reserved Pins: Function + * PA11 USBDM + * PA12 USBDP + * PA13 JTMS-SWDAT + * PA14 JTCK-SWCLK + * PA15 JTDI + * PB2 BOOT1 + * PB3 JTDO + * PB4 JTRST + * PC11 USB_P + * PC12 DISC + * PD0 OSC_IN + * PD1 OSC_OUT + * + * */ +/* Pin STM32 PIN ADC Timer I2C UART SPI F/T + * D0/A6 PA3 ADC3 TIM2_CH4 - USART2_RX - - + * D1/A7 PA2 ADC2 TIM2_CH3 - USART2_TX - - + * D2/A8 PA0 ADC0 TIM2_CH1_ETR - USART2_CTS - - + * D3/A9 PA1 ADC1 TIM2_CH2 - USART2_RTS - - + * D4 PB5 - - ISC1_SMBA - - - + * D5 PB6 - TIM4_CH1 I2C1_SCL - - Y + * D6 PA8 - TIM1_CH1 - USART1_CK - Y + * D7 PA9 - TIM1_CH2 - USART1_TX - Y + * D8 PA10 - TIM1_CH3 - USART1_RX - Y + * D9 PB7 - TIM4_CH2 I2C1_SDA - - Y + * D10/A10 PA4 ADC4 - - USART2_CK SPI1_NSS - + * D11/A11 PA7 ADC7 TIM3_CH2 - - SPI1_MOSI - + * D12/A12 PA6 ADC6 TIM3_CH1 - - SPI1_MISO - + * D13/A13 PA5 ADC5 - - - SPI1_SCK - + * -------------------------------------------------------------------------------------- + * D14/A0 PC0 ADC10 - - - - - + * D15/A1 PC1 ADC11 - - - - - + * D16/A2 PC2 ADC12 - - - - - + * D17/A3 PC3 ADC13 - - - - - + * D18/A4 PC4 ADC14 - - - - - + * D19/A5 PC5 ADC15 - - - - - + * -------------------------------------------------------------------------------------- + * D20/EXT1 PC13 - - - - - - + * D21/EXT2 PC14 - - - - - - + * D22/EXT3 PC15 - - - - - - + * D23/EXT4 PB9 - TIM4_CH4 - - - Y + * D24/EXT5 PD2 - TIM3_ETR - - - Y + * D25/EXT6 PC10 - - - - - Y + * D26/EXT7/A14 PB0 ADC8 TIM3_CH3 - - - - + * D27/EXT8/A15 PB1 ADC9 TIM3_CH4 - - - - + * D28/EXT9 PB10 - - I2C2_SCL USART3_TX - Y + * D29/EXT10 PB11 - - I2C2_SDA USART3_RX - Y + * D30/EXT11 PB12 - TIM1_BKIN I2C2_SMBAL USART3_CK SPI2_NSS Y + * D31/EXT12 PB13 - TIM1_CH1N - USART3_CTS SPI2_SCK Y + * D32/EXT13 PB14 - TIM1_CH2N - USART3_RTS SPI2_MISO Y + * D33/EXT14 PB15 - TIM1_CH3N - - SPI2_MOSI Y + * D34/EXT15 PC6 - - - - - Y + * D35/EXT16 PC7 - - - - - Y + * D36/EXT17 PC8 - - - - - Y + * D37/EXT18 PC9 - - - - - Y + * -------------------------------------------------------------------------------------- + * Note: Silkscreen is marked D15 + * D38 PB8 0 TIM4_CH3 - - - Y + * + * */ + diff --git a/src/lib/adc.c b/src/lib/adc.c new file mode 100644 index 0000000..bcdf874 --- /dev/null +++ b/src/lib/adc.c @@ -0,0 +1,68 @@ +#include "stm32f10x_rcc.h" +#include "adc.h" +#include <stdio.h> +#include <inttypes.h> + +/* The ADC input clock is generated from PCLK2/APB2 divided by a prescaler + * and it must not exceed 14MHz. + * + * ADC1 and ADC2 are clocked by APB2 + * + * 1) Power on by setting ADON in ADC_CR2 + * Conversion starts when ADON is set for a second time after some + * time t > t_stab. + * + * Up to 16 selected conversion must be selected in ADC_SQRx + * + * Single conversion mode: + * Set the ADON bit in the ADC_CR2 register + * Once the conversion is complete: + * Converted data is stored in ADC_DR + * EOC flag is set + * Interrupt is generated if EOCIE is set + * + * Calibration: + * Calibration is started by setting the CAL bit in the ADC_CR2 register. + * Once calibration is over, the CAL bit is reset by hardware and normal + * conversion can be performed. Calibrate at power-on. + * + * ALIGN in ADC_CR2 selects the alignment of data + * + * IMPORTANT: maximum external impedance must be below 0.4kOhms for 1.5 + * sample conversion time. + * + * At 55.5 cycles/sample, the external input impedance < 50kOhms*/ + +void adc_init(void) { + /* PCLK2 is the APB2 clock */ + RCC_ADCCLKConfig(RCC_PCLK2_Div6); + + /* Enable ADC1 clock so that we can talk to it */ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE); + + /* Put everything back to power-on defaults */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, DISABLE); + + ADC_CR1 = 0; + ADC_CR2 = CR2_EXTSEL_SWSTART | CR2_EXTTRIG; // Software triggers conversions + ADC_SQR1 = 0; + + /* Up the sample conversion time to 55.5 cycles/sec, see note above */ + ADC_SMPR1 = 0xB6DB6D; + ADC_SMPR2 = 0x2DB6DB6D; + + /* Enable the ADC */ + CR2_ADON_BIT = 1; + + /* Reset the calibration registers and then perform a reset */ + CR2_RSTCAL_BIT = 1; + while(CR2_RSTCAL_BIT) + ; + + CR2_CAL_BIT = 1; + while(CR2_CAL_BIT) + ; +} + + diff --git a/src/lib/adc.h b/src/lib/adc.h new file mode 100644 index 0000000..41f975e --- /dev/null +++ b/src/lib/adc.h @@ -0,0 +1,67 @@ +#ifndef _ADC_H_ +#define _ADC_H_ +#include <inttypes.h> +#include "util.h" + +#ifdef __cplusplus +extern "C"{ +#endif + +/* Notes: + * The maximum input impedance on each channel MUST be below .4kohms, + * or face the wrath of incorrect readings... + * This can be changed at the expense of sample time... see datasheet + * + * Need to up the sample time if otherwise... see datasheet */ + +/* We'll only use ADC1 for now... */ +#define ADC_BASE 0x40012400 +#define ADC_SR *(volatile uint32_t*)(ADC_BASE + 0) +#define ADC_CR1 *(volatile uint32_t*)(ADC_BASE + 0x4) +#define ADC_CR2 *(volatile uint32_t*)(ADC_BASE + 0x8) +#define ADC_SMPR1 *(volatile uint32_t*)(ADC_BASE + 0xC) +#define ADC_SMPR2 *(volatile uint32_t*)(ADC_BASE + 0x10) +#define ADC_SQR1 *(volatile uint32_t*)(ADC_BASE + 0x2C) +#define ADC_SQR3 *(volatile uint32_t*)(ADC_BASE + 0x34) +#define ADC_DR *(volatile uint32_t*)(ADC_BASE + 0x4C) + +#define CR2_EXTSEL_SWSTART (0xE << 16) +#define CR2_RSTCAL (BIT(3)) +#define CR2_EXTTRIG (BIT(20)) + +/* Bit banded bits */ +#define CR2_ADON_BIT *(volatile uint32_t*)(BITBAND_PERI(ADC_BASE+0x8, 0)) +#define CR2_CAL_BIT *(volatile uint32_t*)(BITBAND_PERI(ADC_BASE+0x8, 2)) +#define CR2_RSTCAL_BIT *(volatile uint32_t*)(BITBAND_PERI(ADC_BASE+0x8, 3)) +#define CR2_SWSTART_BIT *(volatile uint32_t*)(BITBAND_PERI(ADC_BASE+0x8 + 2, 6)) +#define SR_EOC_BIT *(volatile uint32_t*)(BITBAND_PERI(ADC_BASE+0, 1)) + +#define NR_ANALOG_PINS 16 + +/* Initialize ADC1 to do one-shot conversions */ +void adc_init(void); + +/* Perform a single conversion on ADC[0-16], + * PRECONDITIONS: + * adc initialized */ +static inline int adc_read(int channel) { + /* Set channel */ + ADC_SQR3 = channel; + + /* Start the conversion */ + CR2_SWSTART_BIT = 1; + + /* Wait for it to finish */ + while(SR_EOC_BIT == 0) + ; + + return ADC_DR; +} + + + +#ifdef __cplusplus +} // extern "C" +#endif +#endif + diff --git a/src/lib/exti.c b/src/lib/exti.c new file mode 100644 index 0000000..8e46bb1 --- /dev/null +++ b/src/lib/exti.c @@ -0,0 +1,250 @@ +#include "exti.h" +#include "util.h" + +volatile static voidFuncPtr exti_handlers[NR_EXTI_CHANNELS]; + +static inline void clear_pending(int bit) { + REG_SET(EXTI_PR, BIT(bit)); + /* If the pending bit is cleared as the last instruction in an ISR, + * it won't actually be cleared in time and the ISR will fire again. + * Insert a 2-cycle buffer to allow it to take effect. */ + asm volatile("nop"); + asm volatile("nop"); +} + +/* For EXTI0 through EXTI4, only one handler + * is associated with each channel, so we + * don't have to keep track of which channel + * we came from */ +void EXTI0_IRQHandler(void) { + ASSERT(exti_handlers[EXTI0]); + if (exti_handlers[EXTI0]) { + exti_handlers[EXTI0](); + } + + /* Clear pending bit*/ + clear_pending(EXTI0); +} + +void EXTI1_IRQHandler(void) { + ASSERT(exti_handlers[EXTI1]); + /* Call registered handler */ + if (exti_handlers[EXTI1]) { + exti_handlers[EXTI1](); + } + + /* Clear pending bit*/ + clear_pending(EXTI1); +} + +void EXTI2_IRQHandler(void) { + ASSERT(exti_handlers[EXTI2]); + /* Call registered handler */ + if (exti_handlers[EXTI2]) { + exti_handlers[EXTI2](); + } + + /* Clear pending bit*/ + clear_pending(EXTI2); +} + +void EXTI3_IRQHandler(void) { + ASSERT(exti_handlers[EXTI3]); + /* Call registered handler */ + if (exti_handlers[EXTI3]) { + exti_handlers[EXTI3](); + } + + /* Clear pending bit*/ + clear_pending(EXTI3); +} + +void EXTI4_IRQHandler(void) { + ASSERT(exti_handlers[EXTI4]); + /* Call registered handler */ + if (exti_handlers[EXTI4]) { + exti_handlers[EXTI4](); + } + + /* Clear pending bit*/ + clear_pending(EXTI4); +} + +void EXTI9_5_IRQHandler(void) { + /* Figure out which channel it came from */ + uint32_t pending; + uint32_t i; + pending = REG_GET(EXTI_PR); + pending = GET_BITS(pending, 5, 9); + + /* Dispatch every handler if the pending bit is set */ + for (i = 0; i < 5; i++) { + if (pending & 0x1) { + exti_handlers[EXTI5 + i](); + clear_pending(EXTI5 + i); + } + pending >>= 1; + } +} + +void EXTI15_10_IRQHandler(void) { + /* Figure out which channel it came from */ + uint32_t pending; + uint32_t i; + pending = REG_GET(EXTI_PR); + pending = GET_BITS(pending, 10, 15); + + /* Dispatch every handler if the pending bit is set */ + for (i = 0; i < 6; i++) { + if (pending & 0x1) { + exti_handlers[EXTI10 + i](); + clear_pending(EXTI10 + i); + } + pending >>= 1; + } +} + + +void exti_attach_interrupt(uint8_t channel, uint8_t port, voidFuncPtr handler, uint8_t mode) { + ASSERT(channel < NR_EXTI_CHANNELS); + ASSERT(port < NR_EXTI_PORTS); + ASSERT(mode < NR_EXTI_MODES); + ASSERT(EXTI0 == 0); + + /* Note: All of the following code assumes that EXTI0 = 0 */ + + /* Map port to the correct EXTI channel */ + switch (channel) { + case EXTI0: + case EXTI1: + case EXTI2: + case EXTI3: + REG_SET_MASK(AFIO_EXTICR1, BIT_MASK_SHIFT(port, channel*4)); + break; + + case EXTI4: + case EXTI5: + case EXTI6: + case EXTI7: + REG_SET_MASK(AFIO_EXTICR2, BIT_MASK_SHIFT(port, (channel-4)*4)); + break; + + case EXTI8: + case EXTI9: + case EXTI10: + case EXTI11: + REG_SET_MASK(AFIO_EXTICR3, BIT_MASK_SHIFT(port, (channel-8)*4)); + break; + + case EXTI12: + case EXTI13: + case EXTI14: + case EXTI15: + REG_SET_MASK(AFIO_EXTICR4, BIT_MASK_SHIFT(port, (channel-12)*4)); + break; + } + + /* Unmask appropriate interrupt line */ + REG_SET_BIT(EXTI_IMR, channel); + + /* Set trigger mode */ + switch (mode) { + case EXTI_RISING: + REG_SET_BIT(EXTI_RTSR, channel); + break; + + case EXTI_FALLING: + REG_SET_BIT(EXTI_FTSR, channel); + break; + + case EXTI_RISING_FALLING: + REG_SET_BIT(EXTI_RTSR, channel); + REG_SET_BIT(EXTI_FTSR, channel); + break; + } + + /* Configure the enable interrupt bits for the NVIC */ + switch (channel) { + case EXTI0: + case EXTI1: + case EXTI2: + case EXTI3: + case EXTI4: + REG_SET(NVIC_ISER0, BIT(channel + 6)); + break; + + /* EXTI5-9 map to the same isr */ + case EXTI5: + case EXTI6: + case EXTI7: + case EXTI8: + case EXTI9: + REG_SET(NVIC_ISER0, BIT(23)); + break; + + /* EXTI10-15 map to the same isr */ + case EXTI10: + case EXTI11: + case EXTI12: + case EXTI13: + case EXTI14: + case EXTI15: + REG_SET(NVIC_ISER1, BIT(8)); + break; + } + + /* Register the handler */ + exti_handlers[channel] = handler; +} + + +void exti_detach_interrupt(uint8_t channel) { + ASSERT(channel < NR_EXTI_CHANNELS); + ASSERT(EXTI0 == 0); + /* Is this interrupt actually on? */ + ASSERT((REG_GET(EXTI_IMR) >> channel) & 0x01); + + /* Clear EXTI_IMR line */ + REG_CLEAR_BIT(EXTI_IMR, channel); + + /* Clear triggers */ + REG_CLEAR_BIT(EXTI_FTSR, channel); + REG_CLEAR_BIT(EXTI_RTSR, channel); + + /* Turn off the associated interrupt */ + switch (channel) { + case EXTI0: + case EXTI1: + case EXTI2: + case EXTI3: + case EXTI4: + REG_SET(NVIC_ICER0, BIT(channel + 6)); + break; + case EXTI5: + case EXTI6: + case EXTI7: + case EXTI8: + case EXTI9: + /* Are there any other channels enabled? + * If so, don't disable the interrupt handler */ + if (GET_BITS(REG_GET(EXTI_IMR), 5, 9) == 0) { + REG_SET(NVIC_ICER0, BIT(23)); + } + break; + case EXTI10: + case EXTI11: + case EXTI12: + case EXTI13: + case EXTI14: + case EXTI15: + /* Are there any other channels enabled? + * If so, don't disable the interrupt handler */ + if (GET_BITS(REG_GET(EXTI_IMR), 10, 15) == 0) { + REG_SET(NVIC_ICER1, BIT(8)); + } + break; + } + + /* Clear handler function pointer */ + exti_handlers[channel] = 0; +} diff --git a/src/lib/exti.h b/src/lib/exti.h new file mode 100644 index 0000000..ccae3a4 --- /dev/null +++ b/src/lib/exti.h @@ -0,0 +1,143 @@ +#ifndef _EXTI_H_ +#define _EXTI_H_ + +#include <inttypes.h> +/* Notes: + * + * To generate the interrupt, the interrupt line should be configured and + * enabled. This is done by programming the two trigger registers with the + * desired edge detection and by enabling the interrupt request by writing a + * '1' to the corresponding bit in the interrupt mask register. When the + * selected edge occurs on the external interrupt line, an interrupt request is + * generated. The pending bit corresponding to the interrupt line is also set. + * This request is reset by writing a '1' in the pending register. + * + * Hardware interrupt selection: + * To configure the 20 lines as interrupt sources, use the following procedure: + * 1) Configure AFIO_EXTIICR[y] to select the source input for EXTIx external + * interrupt + * 2) Configure the mask bits of the 20 interrupt lines (EXTI_IMR) + * 3) Configure the trigger selection bits of the interrupt lines (EXTI_RTSR and EXTI_FTSR) + * 4) Configure the enable and mask bits that control the NVIC_IRQ channel mapped to the External + * Interrupt Controller (EXTI) so that an inerrupt coming from one of the 20 lines + * can be correctly acknowledged. + * + * AFIO clock must be on. + * + * RM0008, page 107: "PD0, PD1 cannot be used for external interrupt/event generation + * on 36, 48, 64-bin packages." + * + * ---------------------------------------------------------------------------- + * Pin to EXTI Line Mappings: + * EXTI0 EXTI1 EXTI2 EXTI3 EXTI4 + * ---------------------------------------------------------------------------- + * D2/PA0 D3/PA1 D1/PA2 D0/A6/PA3 D10/A10/PA4 + * D26/EXT7/PB0 D27/EXT8/PB1 D16/A2/PC2 D17/A3/PC3 D18/A4/PC4 + * D14/A0/PC0 D15/PC1 D25/EXT5/PD2 + * + * EXTI5 EXTI6 EXTI7 EXTI8 EXTI9 + * ---------------------------------------------------------------------------- + * D13/A13/PA5 D12/A12/PA6 D11/A11/PA7 D6/PA8 D7/PA9 + * D4/PB5 D5/PB6 D9/PB7 D38/PB8 D23/EXT4/PB9 + * D19/A5/PC5 D34/EXTI15/PC6 D35/EXT16/PC7 D36/PC8 D37/EXT18/PC9 + * + * EXTI10 EXTI11 EXTI12 EXTI13 EXTI14 + * ---------------------------------------------------------------------------- + * D8/PA10 D29/EXT10/PB11 D30/EXTI1/PB12 D31/EXTI12/PB13 D32/EXT13/PB14 + * D28/PB10 D20/EXTI1/PC13 D21/EXT2/PC14 + * D25/PC10 + * + * EXTI15 + * ---------------------------------------------------------------------------- + * D33/EXTI14/PB15 + * D22/EXT3/PC15 + * + * + * The 16 EXTI interrupts are mapped to 7 interrupt handlers. + * + * EXTI Lines to Interrupt Mapping: + * EXTI0 -> EXTI0 + * EXTI1 -> EXTI1 + * EXTI2 -> EXTI2 + * EXTI3 -> EXTI3 + * EXTI4 -> EXTI4 + * EXTI[5-9] -> EXT9_5 + * EXTI[10-15] -> EXT15_10 + * + * + * */ + +#define NR_EXTI_CHANNELS 16 +#define NR_EXTI_PORTS 4 +#define NR_EXTI_MODES 3 + +#define EXTI_IMR 0x40010400 // Interrupt mask register +#define EXTI_EMR (EXTI_IMR + 0x04) // Event mask register +#define EXTI_RTSR (EXTI_IMR + 0x08) // Rising trigger selection register +#define EXTI_FTSR (EXTI_IMR + 0x0C) // Falling trigger selection register +#define EXTI_SWIER (EXTI_IMR + 0x10) // Software interrupt event register +#define EXTI_PR (EXTI_IMR + 0x14) // Pending register + +#define AFIO_EVCR 0x40010000 +#define AFIO_EXTICR1 (AFIO_EVCR + 0x08) +#define AFIO_EXTICR2 (AFIO_EVCR + 0x0C) +#define AFIO_EXTICR3 (AFIO_EVCR + 0x10) +#define AFIO_EXTICR4 (AFIO_EVCR + 0x14) + +#define NVIC_EXTI1_OFFSET (NVIC_ISER0 + 0x07) +#define NVIC_EXTI9_5_OFFSET (NVIC_ISER0 + 0x17) + +/* NVIC Interrupt Enable registers */ +#define NVIC_ISER0 0xE000E100 +#define NVIC_ISER1 0xE000E104 +#define NVIC_ISER2 0xE000E108 +#define NVIC_ISER3 0xE000E10C + +/* NVIC Interrupt Clear registers */ +#define NVIC_ICER0 0xE000E180 +#define NVIC_ICER1 0xE000E184 +#define NVIC_ICER2 0xE000E188 +#define NVIC_ICER3 0xE000E18C + +#define EXTI_RISING 0 +#define EXTI_FALLING 1 +#define EXTI_RISING_FALLING 2 + +#define EXTI0 0 +#define EXTI1 1 +#define EXTI2 2 +#define EXTI3 3 +#define EXTI4 4 +#define EXTI5 5 +#define EXTI6 6 +#define EXTI7 7 +#define EXTI8 8 +#define EXTI9 9 +#define EXTI10 10 +#define EXTI11 11 +#define EXTI12 12 +#define EXTI13 13 +#define EXTI14 14 +#define EXTI15 15 + +#define EXTI_CONFIG_PORTA 0 +#define EXTI_CONFIG_PORTB 1 +#define EXTI_CONFIG_PORTC 2 +#define EXTI_CONFIG_PORTD 3 + +typedef void (*voidFuncPtr)(void); + +#ifdef __cplusplus +extern "C"{ +#endif + +void exti_attach_interrupt(uint8_t, uint8_t, voidFuncPtr, uint8_t); +void exti_detach_interrupt(uint8_t); + +#ifdef __cplusplus +} // extern "C" +#endif + + +#endif + diff --git a/src/lib/gpio.c b/src/lib/gpio.c new file mode 100644 index 0000000..db511c4 --- /dev/null +++ b/src/lib/gpio.c @@ -0,0 +1,14 @@ +#include "wiring.h" +#include "stm32f10x_rcc.h" +#include "gpio.h" +#include "util.h" + +void gpio_init(void) { + /* Turn on clocks for GPIO */ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | + RCC_APB2Periph_GPIOB | + RCC_APB2Periph_GPIOC | + RCC_APB2Periph_AFIO, + ENABLE); +} + diff --git a/src/lib/gpio.h b/src/lib/gpio.h new file mode 100644 index 0000000..7620f96 --- /dev/null +++ b/src/lib/gpio.h @@ -0,0 +1,100 @@ +#ifndef _GPIO_H +#define _GPIO_H + +#include <inttypes.h> +#include "util.h" + + +/* Each of the GPIO port bits can be in the following modes (STM32 138/995): + * Input floating + * Input pull-up + * Input pull-down + * Analog Input + * Output open-drain + * Output push-pull + * Alternate function push-pull + * Alternate function open-drain + * + * - After reset, the alternate functions are not active and IO prts + * are set to Input Floating mode */ + +#define _GPIOA_BASE (GPIO_Port*)0x40010800 +#define _GPIOB_BASE (GPIO_Port*)0x40010C00 +#define _GPIOC_BASE (GPIO_Port*)0x40011000 +#define _GPIOD_BASE (GPIO_Port*)0x40011400 + +/* Pin modes are set by [CNFx[1:0] : MODEx[1:0]] */ +#define GPIO_SPEED_50MHZ (0x3) // Max output speed 50 MHz +#define GPIO_MODE_OUTPUT_PP ((0x00 << 2) | GPIO_SPEED_50MHZ) +#define GPIO_MODE_OUTPUT_OD ((0x01 << 2) | GPIO_SPEED_50MHZ) + +#define GPIO_MODE_AF_OUTPUT_PP ((0x02 << 2) | GPIO_SPEED_50MHZ) +#define GPIO_MODE_AF_OUTPUT_OD ((0x03 << 2) | GPIO_SPEED_50MHZ) + +/* Note: mode bits must be set to zero for input mode */ +#define GPIO_MODE_INPUT_ANALOG (0x00 << 2) +#define GPIO_MODE_INPUT_FLOATING (0x01 << 2) +#define GPIO_MODE_INPUT_PD (0x02 << 2) +#define GPIO_MODE_INPUT_PU (0x02 << 2) + +#define INPUT_ANALOG GPIO_MODE_INPUT_ANALOG +#define INPUT_DIGITAL GPIO_MODE_INPUT_FLOATING +#define INPUT_FLOATING GPIO_MODE_INPUT_FLOATING +#define INPUT_PULLDOWN GPIO_MODE_INPUT_PD +#define INPUT_PULLUP GPIO_MODE_INPUT_PU +#define INPUT GPIO_MODE_INPUT_FLOATING +#define OUTPUT GPIO_MODE_OUTPUT_PP + +typedef struct { + volatile uint32_t CRL; // Port configuration register low + volatile uint32_t CRH; // Port configuration register high + volatile uint32_t IDR; // Port input data register + volatile uint32_t ODR; // Port output data register + volatile uint32_t BSRR; // Port bit set/reset register + volatile uint32_t BRR; // Port bit reset register + volatile uint32_t LCKR; // Port configuration lock register +} GPIO_Port; + +typedef volatile uint32_t* GPIOReg; + +#define POS_MASK(shift) (~(0xF << shift)) +#define POS(val) (val << 2) + +#ifdef __cplusplus +extern "C"{ +#endif + +void gpio_init(void); + +static inline void gpio_set_mode(GPIO_Port* port, uint8_t gpio_pin, uint8_t mode) { + uint32_t tmp; + uint32_t shift = POS(gpio_pin % 8); + GPIOReg CR; + + ASSERT(port); + ASSERT(gpio_pin < 16); + + CR = (gpio_pin < 8) ? &(port->CRL) : &(port->CRH); + + tmp = *CR; + tmp &= POS_MASK(shift); + tmp |= mode << shift; + + *CR = tmp; +} + +static inline void gpio_write_bit(GPIO_Port *port, uint8_t gpio_pin, uint8_t val) { + if (val){ + port->BSRR = BIT(gpio_pin); + } else { + port->BRR = BIT(gpio_pin); + } +} + +#ifdef __cplusplus +} // extern "C" +#endif + + +#endif + diff --git a/src/lib/stm32f10x_conf.h b/src/lib/stm32f10x_conf.h new file mode 100644 index 0000000..d523f1a --- /dev/null +++ b/src/lib/stm32f10x_conf.h @@ -0,0 +1,132 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/* #define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+#define _ADC
+#define _ADC1
+#define _ADC2
+#define _ADC3
+//#define _BKP
+//#define _CAN
+//#define _CRC
+//#define _DAC
+//#define _DBGMCU
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+#define _EXTI
+#define _FLASH
+
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+#if 0
+#define _FSMC
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+#define _GPIOD
+#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _I2C
+#define _I2C1
+#define _I2C2
+#define _IWDG
+#define _PWR
+#define _RTC
+#define _SDIO
+#define _SPI
+#define _SPI1
+#define _SPI2
+#define _SPI3
+#define _SysTick
+#define _TIM
+#define _TIM1
+#define _TIM2
+#define _TIM3
+#define _TIM4
+#define _TIM5
+#define _TIM6
+#define _TIM7
+#define _TIM8
+#define _USART
+#define _USART1
+#define _USART3
+#define _UART4
+#define _UART5
+#endif
+#define _USART2
+#define _NVIC
+#define _RCC
+#define _AFIO
+
+/************************************* WWDG ***********************************/
+#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/lib/stm32f10x_it.c b/src/lib/stm32f10x_it.c new file mode 100644 index 0000000..70d3269 --- /dev/null +++ b/src/lib/stm32f10x_it.c @@ -0,0 +1,252 @@ +void NMIException(void) {
+}
+void HardFaultException(void) {
+ while (1) {
+ }
+}
+
+void MemManageException(void) {
+ while (1) {
+ }
+}
+
+void BusFaultException(void) {
+ while (1) {
+ }
+}
+
+void UsageFaultException(void) {
+ while (1) {
+ }
+}
+
+#if 0
+void DebugMonitor(void) {
+}
+
+void SVCHandler(void) {
+}
+
+void PendSVC(void) {
+}
+
+void WWDG_IRQHandler(void) {
+}
+
+void PVD_IRQHandler(void) {
+}
+
+void TAMPER_IRQHandler(void) {
+}
+
+void RTC_IRQHandler(void) {
+}
+
+void FLASH_IRQHandler(void) {
+}
+
+void RCC_IRQHandler(void) {
+}
+
+void DMA1_Channel1_IRQHandler(void) {
+}
+
+void DMA1_Channel2_IRQHandler(void) {
+}
+
+void DMA1_Channel3_IRQHandler(void) {
+}
+
+void DMA1_Channel4_IRQHandler(void) {
+}
+
+void DMA1_Channel5_IRQHandler(void) {
+}
+
+void DMA1_Channel6_IRQHandler(void) {
+}
+
+void DMA1_Channel7_IRQHandler(void) {
+}
+
+void ADC1_2_IRQHandler(void) {
+}
+
+void USB_HP_CAN_TX_IRQHandler(void) {
+}
+
+void USB_LP_CAN_RX0_IRQHandler(void) {
+}
+
+void CAN_RX1_IRQHandler(void) {
+}
+
+void CAN_SCE_IRQHandler(void) {
+}
+
+void TIM1_BRK_IRQHandler(void) {
+}
+
+void TIM1_UP_IRQHandler(void) {
+ while(1) {
+ }
+}
+
+void TIM1_TRG_COM_IRQHandler(void) {
+}
+
+void TIM1_CC_IRQHandler(void) {
+ while(1)
+ ;
+}
+
+void TIM2_IRQHandler(void) {
+}
+
+void TIM3_IRQHandler(void) {
+}
+
+void TIM4_IRQHandler(void) {
+}
+
+void I2C1_EV_IRQHandler(void) {
+}
+
+void I2C1_ER_IRQHandler(void) {
+}
+
+void I2C2_EV_IRQHandler(void) {
+}
+
+void I2C2_ER_IRQHandler(void) {
+}
+
+void SPI1_IRQHandler(void) {
+}
+
+void SPI2_IRQHandler(void) {
+}
+
+void USART1_IRQHandler(void) {
+#if 0
+ if(USART_GetITStatus(USART1, USART_IT_RXNE) != RESET)
+ {
+ /* Read one byte from the receive data register */
+ RxBuffer[RxCounter++] = (USART_ReceiveData(USART1) & 0x7F);
+
+ if(RxCounter == NbrOfDataToRead)
+ {
+ /* Disable the USART Receive interrupt */
+ USART_ITConfig(USART1, USART_IT_RXNE, DISABLE);
+ }
+ }
+
+ if(USART_GetITStatus(USART1, USART_IT_TXE) != RESET)
+ {
+ /* Write one byte to the transmit data register */
+ USART_SendData(USART1, TxBuffer[TxCounter++]);
+
+ if(TxCounter == NbrOfDataToTransfer)
+ {
+ /* Disable the USART1 Transmit interrupt */
+ USART_ITConfig(USART1, USART_IT_TXE, DISABLE);
+ }
+ }
+#endif
+}
+
+void USART2_IRQHandler(void) {
+#if 0
+ if(USART_GetITStatus(USART2, USART_IT_RXNE) != RESET)
+ {
+ /* Echo the character back */
+ RxBuffer[0] = (USART_ReceiveData(USART2) & 0x7F);
+ USART_SendData(USART2, RxBuffer[0]);
+ // /* Read one byte from the receive data register */
+ // RxBuffer[RxCounter++] = (USART_ReceiveData(USART2) & 0x7F);
+
+ // if(RxCounter == NbrOfDataToRead)
+ // {
+ // /* Disable the USART Receive interrupt */
+ // USART_ITConfig(USART2, USART_IT_RXNE, DISABLE);
+ // }
+ }
+
+#endif
+
+#if 0
+ if(USART_GetITStatus(USART2, USART_IT_TXE) != RESET)
+ {
+ /* Write one byte to the transmit data register */
+ USART_SendData(USART2, 'Y');
+ TxCounter++;
+// USART_SendData(USART2, TxBuffer[TxCounter++]);
+
+ if(TxCounter == NbrOfDataToTransfer) {
+ /* Disable the USART1 Transmit interrupt */
+ USART_ITConfig(USART2, USART_IT_TXE, DISABLE);
+ }
+ }
+#endif
+}
+
+void USART3_IRQHandler(void) {
+}
+
+void RTCAlarm_IRQHandler(void) {
+}
+
+void USBWakeUp_IRQHandler(void) {
+}
+
+void TIM8_BRK_IRQHandler(void) {
+}
+
+void TIM8_UP_IRQHandler(void) {
+}
+
+void TIM8_TRG_COM_IRQHandler(void) {
+}
+
+void TIM8_CC_IRQHandler(void) {
+}
+
+void ADC3_IRQHandler(void) {
+}
+
+void FSMC_IRQHandler(void) {
+}
+
+void SDIO_IRQHandler(void) {
+}
+
+void TIM5_IRQHandler(void) {
+}
+
+void SPI3_IRQHandler(void) {
+}
+
+void UART4_IRQHandler(void) {
+}
+
+void UART5_IRQHandler(void) {
+}
+
+void TIM6_IRQHandler(void) {
+}
+
+void TIM7_IRQHandler(void) {
+}
+
+void DMA2_Channel1_IRQHandler(void) {
+}
+
+void DMA2_Channel2_IRQHandler(void) {
+}
+
+void DMA2_Channel3_IRQHandler(void) {
+}
+
+void DMA2_Channel4_5_IRQHandler(void) {
+}
+#endif
diff --git a/src/lib/syscalls.c b/src/lib/syscalls.c new file mode 100644 index 0000000..6095bd3 --- /dev/null +++ b/src/lib/syscalls.c @@ -0,0 +1,156 @@ +#include <sys/stat.h> +#include "stm32f10x_usart.h" + +/* _end is set in the linker command file */ +extern caddr_t _end; + +/* just in case, most boards have at least some memory */ +#ifndef RAMSIZE +# define RAMSIZE (caddr_t)0x50000 +#endif + +#define STACK_TOP 0x20000800 + +void uart_send(const char*str); + +/* + * sbrk -- changes heap size size. Get nbytes more + * RAM. We just increment a pointer in what's + * left of memory on the board. + */ +caddr_t +_sbrk(nbytes) +int nbytes; +{ + static caddr_t heap_ptr = NULL; + caddr_t base; + + if (heap_ptr == NULL) { + heap_ptr = (caddr_t)&_end; + } + + if ((STACK_TOP - (unsigned int)heap_ptr) >= 0) { + base = heap_ptr; + heap_ptr += nbytes; + return (base); + } else { + uart_send("heap full!\r\n"); + return ((caddr_t)-1); + } +} + +int _open(const char *path, int flags, ...) +{ + return 1; +} + +int _close(int fd) +{ + return 0; +} + +int _fstat(int fd, struct stat *st) +{ + st->st_mode = S_IFCHR; + return 0; +} + +int _isatty(int fd) +{ + return 1; +} + +int isatty(int fd) +{ + return 1; +} + +int _lseek(int fd, off_t pos, int whence) +{ + return -1; +} + +unsigned char getch(void) +{ + while (!(USART2->SR & USART_FLAG_RXNE)); + return USART2->DR; +} + + +int _read(int fd, char *buf, size_t cnt) +{ + *buf = getch(); + + return 1; +} + +void putch(unsigned char c) +{ + if (c == '\n') putch('\r'); + + while (!(USART2->SR & USART_FLAG_TXE)); + USART2->DR = c; +} + +void cgets(char *s, int bufsize) +{ + char *p; + int c; + int i; + + for (i = 0; i < bufsize; i++) { + *(s+i) = 0; + } +// memset(s, 0, bufsize); + + p = s; + + for (p = s; p < s + bufsize-1;) + { + c = getch(); + switch (c) + { + case '\r' : + case '\n' : + putch('\r'); + putch('\n'); + *p = '\n'; + return; + + case '\b' : + if (p > s) + { + *p-- = 0; + putch('\b'); + putch(' '); + putch('\b'); + } + break; + + default : + putch(c); + *p++ = c; + break; + } + } + return; +} + +int _write(int fd, const char *buf, size_t cnt) +{ + int i; +// uart_send("_write\r\n"); + + for (i = 0; i < cnt; i++) + putch(buf[i]); + + return cnt; +} + +/* Override fgets() in newlib with a version that does line editing */ +char *fgets(char *s, int bufsize, void *f) +{ +// uart_send("fgets\r\n"); + cgets(s, bufsize); + return s; +} diff --git a/src/lib/systick.c b/src/lib/systick.c new file mode 100644 index 0000000..f328ae0 --- /dev/null +++ b/src/lib/systick.c @@ -0,0 +1,30 @@ +#include "systick.h" + +#define MILLIS_INC 1 + +volatile uint32_t systick_timer_overflow_count = 0; +volatile uint32_t systick_timer_millis = 0; +static uint8_t systick_timer_fract = 0; + +void systick_init(void) { + /* Set the reload counter to tick every 1ms */ + SYSTICK_RELOAD = MAPLE_RELOAD_VAL; + + /* Clock the system timer with the core clock + * and turn it on, interrrupt every 1ms to keep track of millis()*/ + SYSTICK_CSR = SYSTICK_SRC_HCLK | + SYSTICK_ENABLE | + SYSTICK_TICKINT; +} + +void SysTickHandler(void) +{ + uint32_t m = systick_timer_millis; + uint8_t f = systick_timer_fract; + + m += MILLIS_INC; + systick_timer_millis = m; + systick_timer_overflow_count++; +} + + diff --git a/src/lib/systick.h b/src/lib/systick.h new file mode 100644 index 0000000..42d33d0 --- /dev/null +++ b/src/lib/systick.h @@ -0,0 +1,37 @@ +#ifndef _SYSTICK_H_ +#define _SYSTICK_H_ +#include <inttypes.h> +#include "util.h" + +/* To the ARM technical manual... there's nearly nothing on the systick + * timer in the stm32 manual */ + +#define SYSTICK_CSR *(volatile int*)0xE000E010 // Control and status register +#define SYSTICK_RELOAD *(volatile int*)0xE000E014 // Reload value register +#define SYSTICK_CNT *(volatile int*)0xE000E018 // Current value register +#define SYSTICK_CALIB *(volatile int*)0xE000E01C // Calibration value register + +#define SYSTICK_SRC_HCLK BIT(2) // Use core clock +#define SYSTICK_TICKINT BIT(1) // Interrupt on systick countdown +#define SYSTICK_ENABLE BIT(0) // Turn on the counter + +/* We use the systick timer to tick once + * every millisecond */ +#define MAPLE_RELOAD_VAL 72000 + +#ifdef __cplusplus +extern "C"{ +#endif + +void systick_init(void); + +static inline uint32_t systick_get_count(void) { + return (uint32_t)SYSTICK_CNT; +} + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif + diff --git a/src/lib/timers.c b/src/lib/timers.c new file mode 100644 index 0000000..401b267 --- /dev/null +++ b/src/lib/timers.c @@ -0,0 +1,114 @@ +#include "stm32f10x_rcc.h" +#include "wiring.h" +#include "timers.h" +#include "util.h" + +typedef struct { + volatile uint16_t CR1; + uint16_t RESERVED0; + volatile uint16_t CR2; + uint16_t RESERVED1; + volatile uint16_t SMCR; + uint16_t RESERVED2; + volatile uint16_t DIER; + uint16_t RESERVED3; + volatile uint16_t SR; + uint16_t RESERVED4; + volatile uint16_t EGR; + uint16_t RESERVED5; + volatile uint16_t CCMR1; + uint16_t RESERVED6; + volatile uint16_t CCMR2; + uint16_t RESERVED7; + volatile uint16_t CCER; + uint16_t RESERVED8; + volatile uint16_t CNT; + uint16_t RESERVED9; + volatile uint16_t PSC; + uint16_t RESERVED10; + volatile uint16_t ARR; + uint16_t RESERVED11; + volatile uint16_t RCR; + uint16_t RESERVED12; + volatile uint16_t CCR1; + uint16_t RESERVED13; + volatile uint16_t CCR2; + uint16_t RESERVED14; + volatile uint16_t CCR3; + uint16_t RESERVED15; + volatile uint16_t CCR4; + uint16_t RESERVED16; + volatile uint16_t BDTR; // Not used in general purpose timers + uint16_t RESERVED17; // Not used in general purpose timers + volatile uint16_t DCR; + uint16_t RESERVED18; + volatile uint16_t DMAR; + uint16_t RESERVED19; +} Timer; + +void timer_init(uint8_t timer_num, uint16_t prescale) { + Timer *timer; + uint32_t is_advanced = 0; + + ASSERT(timer_num > 0 && timer_num <= 4); + + switch(timer_num) { + case 1: + timer = (Timer*)TIMER1_BASE; + RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE); + is_advanced = 1; + break; + case 2: + timer = (Timer*)TIMER2_BASE; + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); + break; + case 3: + timer = (Timer*)TIMER3_BASE; + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); + break; + case 4: + timer = (Timer*)TIMER4_BASE; + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); + break; + } + + timer->CR1 = ARPE; // No clock division + // Do not buffer auto-reload preload + // Edge aligned + // Upcounter + // Do not stop counter at update event + // Update events enabled (etc, see bits [1:2]) + // Counter disabled for now + + timer->PSC = prescale; // Prescaling by prescale (duh) + timer->ARR = 0xFFFF; // Max reload cont + + /* initialize all the channels to 50% duty cycle, + * TODO: none of them actually get output unless the gpio pin + * is set, this will probably consume a bit more power but + * we'll worry about that later. */ + timer->CCR1 = 0x8FFF; // PWM start value + timer->CCMR1 |= 0x68; // PWM mode 1, enable preload register. + timer->CCER |= 0x001; // enable ch + + timer->CCR2 = 0x8FFF; // PWM start value + timer->CCMR1 |= (0x68 << 8);// PWM mode 1, enable preload register. + timer->CCER |= 0x010; // enable ch + + timer->CCR3 = 0x8FFF; // PWM start value + timer->CCMR2 |= 0x68; // PWM mode 1, enable preload register. + timer->CCER |= 0x100; // enable ch + + timer->CCR4 = 0x8FFF; // PWM start value + timer->CCMR2 |= (0x68 << 8);// PWM mode 1, enable preload register. + timer->CCER |= 0x1000; // enable ch + + /* Advanced timer? */ + if (is_advanced) { + timer->BDTR = 0x8000; // moe enable + } + + timer->DIER = 0; // disable update interrupt + timer->EGR = 1; // Initialize update event and shadow registers + timer->CR1 |= 1; // Enable timer +} diff --git a/src/lib/timers.h b/src/lib/timers.h new file mode 100644 index 0000000..27e5999 --- /dev/null +++ b/src/lib/timers.h @@ -0,0 +1,118 @@ +/* Note to self: + * The timer clock frequencies are automatically fixed by hardware. + * There are two cases: + * 1. if the APB prescaler is 1, the timer clock frequencies are + * set to the same frequency as that of the APB domain to which + * the timers are connected. + * 2. otherwise, they are set to twice (x2) the frequency of the + * APB domain to which the timers are connected. + * See stm32 manual, 77/995 + * + * hence, 72 mhz timers + * */ + +/* Maple Timer channels: + * Timer Maple Pin STM32 Pin Type + * TIM1_CH1 D6 PA8 Advanced + * TIM1_CH2 D7 PA9 Advanced + * TIM1_CH3 D8 PA10 Advanced + * + * TIM2_CH1 D2 PA0 + * TIM2_CH2 D3 PA1 + * TIM2_CH3 D1 PA2 + * TIM2_CH4 D0 PA3 + * + * TIM3_CH1 D12 PA6 + * TIM3_CH2 D11 PA7 + * TIM3_CH3 EXT7 PB0 + * TIM3_CH4 EXT8 PB1 + * + * TIM4_CH1 EXT5 PB6 + * TIM4_CH1 EXT9 PB7 + * TIM4_CH1 EXT15 PB8 + * TIM4_CH1 EXT4 PB9 + * + * Not supported: + * TIM1_CH4 USBDM, not available PA11 Advanced + * TIM1_CH1_N EXT12 PB13 + * TIM1_CH2_N EXT13 PB14 + * TIM1_CH3_N EXT14 PB15 + * */ + +/* I don't like the Arduino API for dealing with pin modes. + * How about... + * + * pinMode(digitalPin, PWM); + * pwmWrite(digitalPin) */ + + +#ifndef _TIMERS_H_ +#define _TIMERS_H_ +#include <inttypes.h> + +#ifdef __cplusplus +extern "C"{ +#endif + +typedef volatile uint32_t* TimerCCR; + +#define TIMER1_BASE 0x40012C00 +#define TIMER2_BASE 0x40000000 +#define TIMER3_BASE 0x40000400 +#define TIMER4_BASE 0x40000800 + +#define ARPE BIT(7) // Auto-reload preload enable +#define NOT_A_TIMER 0 + +#define TIMER1_CH1_CCR (TimerCCR)(TIMER1_BASE + 0x34) +#define TIMER1_CH2_CCR (TimerCCR)(TIMER1_BASE + 0x38) +#define TIMER1_CH3_CCR (TimerCCR)(TIMER1_BASE + 0x3C) +#define TIMER1_CH4_CCR (TimerCCR)(TIMER1_BASE + 0x40) + +#define TIMER2_CH1_CCR (TimerCCR)(TIMER2_BASE + 0x34) +#define TIMER2_CH2_CCR (TimerCCR)(TIMER2_BASE + 0x38) +#define TIMER2_CH3_CCR (TimerCCR)(TIMER2_BASE + 0x3C) +#define TIMER2_CH4_CCR (TimerCCR)(TIMER2_BASE + 0x40) + +#define TIMER3_CH1_CCR (TimerCCR)(TIMER3_BASE + 0x34) +#define TIMER3_CH2_CCR (TimerCCR)(TIMER3_BASE + 0x38) +#define TIMER3_CH3_CCR (TimerCCR)(TIMER3_BASE + 0x3C) +#define TIMER3_CH4_CCR (TimerCCR)(TIMER3_BASE + 0x40) + +#define TIMER4_CH1_CCR (TimerCCR)(TIMER4_BASE + 0x34) +#define TIMER4_CH2_CCR (TimerCCR)(TIMER4_BASE + 0x38) +#define TIMER4_CH3_CCR (TimerCCR)(TIMER4_BASE + 0x3C) +#define TIMER4_CH4_CCR (TimerCCR)(TIMER4_BASE + 0x40) + + +/* Turn on timer with prescale as the divisor + * void timer_init(uint32_t timer, uint16_t prescale) + * timer -> {1-4} + * prescale -> {1-65535} + * */ +void timer_init(uint8_t, uint16_t); + +/* Turn on PWM with duty_cycle on the specified channel in timer. + * This function takes in a pointer to the corresponding CCR + * register for the pin cause it saves pwmWrite() a couple of + * cycles. + * + * void timer_pwm(uint8_t channel, uint8_t duty_cycle); + * channel -> {TIMERx_CHn_CCR} + * duty_cycle -> {0-65535} + * + * PRECONDITIONS: + * pin has been set to alternate function output + * timer has been initialized + */ +static inline void timer_pwm_write_ccr(TimerCCR CCR, uint16_t duty_cycle) { + *CCR = duty_cycle; +} + +#ifdef __cplusplus +} // extern "C" +#endif + + +#endif + diff --git a/src/lib/usart.c b/src/lib/usart.c new file mode 100644 index 0000000..c1a7f43 --- /dev/null +++ b/src/lib/usart.c @@ -0,0 +1,44 @@ +#include "stm32f10x_rcc.h" +#include "usart.h" + +static inline void usart_putc(usart_port *port, uint8_t ch) { + port->DR = ch; + + /* Wait till TXE = 1 */ + while ((port->SR & USART_TXE) == 0) + ; +} + +int32_t usart_init(uint8_t usart_num) { + ASSERT((usart_num < NR_USARTS) && (usart_num > 0)); + usart_port *port; + uint32_t clk_speed; + + switch (usart_num) { + case 1: + port = USART1_BASE; + clk_speed = USART1_CLK; + break; + case 2: + port = USART2_BASE; + clk_speed = USART2_CLK; + RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); + break; + case 3: + port = USART3_BASE; + break; + default: + /* should never get here */ + ASSERT(0); + } + uint32_t baud = 9600; + uint32_t usartdiv = clk_speed / baud; + + /* Set baud rate */ + port->BRR = BIT_MASK_SHIFT(B9600_MANTISSA, 4) | B9600_FRACTION; + + /* Enable the USART and set 8n1 (M bit clear) enable transmitter*/ + port->CR1 = USART_UE | USART_TE; + + return 0; +} diff --git a/src/lib/usart.h b/src/lib/usart.h new file mode 100644 index 0000000..30f7dc1 --- /dev/null +++ b/src/lib/usart.h @@ -0,0 +1,131 @@ +#ifndef _USART_H_ +#define _USART_H_ +#include <inttypes.h> +#include <util.h> + +/* Transmit procedure: + * 1. Enable the USART by writing the UE bit in USART_CR1 register to 1. + * + * 2. Program the M bit in USART_CR1 to define the word length. + * + * 3. Program the number of stop bits in USART_CR2. + * + * 4. Select DMA enable (DMAT) in USART_CR3 if Multi buffer Communication is + * to take place. Configure the DMA register as explained in multibuffer + * communication. + * + * 5. Select the desired baud rate using the USART_BRR register. + * + * 6. Set the TE bit in USART_CR1 to send an idle frame as first transmission. + * + * 7. Write the data to send in the USART_DR register (this clears the TXE + * bit). Repeat this for each data to be transmitted in case of single buffer. + * + * 8. After writing the last data into the USART_DR register, wait until TC=1. + * This indicates that the transmission of the last frame is complete. This is + * required for instance when the USART is disabled or enters the Halt mode to + * avoid corrupting the last transmission. + * + * Single byte communication + * Clearing the TXE bit is always performed by a write to the data register. + * + * The TXE bit is set by hardware and it indicates: + * ? The data has been moved from TDR to the shift register and the data transmission has + * started. + * ? The TDR register is empty. + * ? The next data can be written in the USART_DR register without overwriting the + * previous data. + * This flag generates an interrupt if the TXEIE bit is set. + * + * When a transmission is taking place, a write instruction to the USART_DR + * register stores the data in the TDR register and which is copied in the + * shift register at the end of the current transmission. + * + * When no transmission is taking place, a write instruction to the USART_DR + * register places the data directly in the shift register, the data + * transmission starts, and the TXE bit is immediately set. + * + * If a frame is transmitted (after the stop bit) and the TXE bit is set, the + * TC bit goes high. An interrupt is generated if the TCIE bit is set in the + * USART_CR1 register. After writing the last data into the USART_DR register, + * it is mandatory to wait for TC=1 before disabling the USART or causing the + * microcontroller to enter the low power mode (see Figure 241: TC/TXE behavior + * when transmitting). + * + * Clearing the TC bit is performed by the following software sequence: + * 1. A read from the USART_SR register + * 2. A write to the USART_DR register + * + * + * For now, use 8N1 + * + * Baud rate is generated by programming the mantissa and fraction values of + * USARTDIV + * + * baud = fck / 16*USARTDIV + * Fck = PLK1 for USART2 and USART3 = 36MHz + * Fck = PCLK2 for USART1 = 72MHz + * + * Baud Actual USARTDIV_36MHZ Error USARTDIV_72MHZ Error + * 2400 2.400 937.5 0% 1875 0% + * 9600 9.600 234.375 0% 468.75 0% + * 19200 19.2 117.1875 0% 234.375 0% + * 57600 57.6 39.0625 0% 78.125 0.% + * 115200 115.384 19.5 0.15% 39.0625 0% + * 230400 230.769 9.75 0.16% 19.5 0.16% + * 460800 461.538 4.875 0.16% 9.75 0.16% + * 921600 923.076 2.4375 0.16% 4.875 0.16% + * 225000 2250 1 0% 2 0% + * + * USART_BRR[15:4] = mantissa + * USART_BRR[3:0] = fraction + * 111010 + * 0110 + * */ +#define NR_USARTS 0x3 + +//#define USART1_BASE 0x40013800 +//#define USART2_BASE 0x40004400 +//#define USART3_BASE 0x40004800 + +#define USART_UE BIT(13) +#define USART_M BIT(12) +#define USART_TE BIT(3) +#define USART_TXE BIT(7) +#define USART_STOP_BITS_1 BIT_MASK_SHIFT(0b0, 12) +#define USART_STOP_BITS_05 BIT_MASK_SHIFT(0b01, 12) +#define USART_STOP_BITS_2 BIT_MASK_SHIFT(0b02, 12) +#define USART_STOP_BITS_15 BIT_MASK_SHIFT(0b02, 12) + +#define USART1_CLK 72000000UL +#define USART2_CLK 36000000UL +#define USART3_CLK 36000000UL + +#define B9600_MANTISSA 0xEA +#define B9600_FRACTION 0x06 + + +typedef struct usart_port { + volatile uint32_t SR; + volatile uint32_t DR; + volatile uint32_t BRR; + volatile uint32_t CR1; + volatile uint32_t CR2; + volatile uint32_t CR3; + volatile uint32_t GTPR; +} usart_port; + +#ifdef __cplusplus +extern "C"{ +#endif + +int32_t usart_init(uint8_t); + + +#ifdef __cplusplus +} // extern "C" +#endif + + +#endif + diff --git a/src/lib/util.cpp b/src/lib/util.cpp new file mode 100644 index 0000000..4eb4fe0 --- /dev/null +++ b/src/lib/util.cpp @@ -0,0 +1,47 @@ +#include "wiring.h" +#include "Serial.h" +#include "util.h" +#include "io.h" + +#define ERROR_PIN 13 + +/* Required for C++ hackery */ +extern "C" void __cxa_pure_virtual(void) { + while(1) + ; +} + +/* Error assert + fade */ +void _fail(const char* file, int line, const char* exp) { + int32_t slope = 1; + int32_t CC = 0x0000; + int32_t TOP_CNT = 0x02FF; + int32_t i = 0; + + Serial1.print("ERROR: FAILED ASSERT("); + Serial1.print(exp); + Serial1.print("): "); + Serial1.print(file); + Serial1.print(":"); + Serial1.println(line); + + while (1) { + if (CC == TOP_CNT) { + slope = -1; + } else if (CC == 0) { + slope = 1; + } + + if (i == TOP_CNT) { + CC += slope; + i = 0; + } + + if (i < CC) { + digitalWrite(ERROR_PIN, HIGH); + } else { + digitalWrite(ERROR_PIN, LOW); + } + i++; + } +} diff --git a/src/lib/util.h b/src/lib/util.h new file mode 100644 index 0000000..8701af1 --- /dev/null +++ b/src/lib/util.h @@ -0,0 +1,57 @@ +/* Generally "useful" utility procedures */ +#ifndef _UTIL_H_ +#define _UTIL_H_ +#include <inttypes.h> + +#define MAPLE_DEBUG 1 + +#define BIT(shift) (1 << (shift)) +#define BIT_MASK_SHIFT(mask, shift) ((mask) << (shift)) + +/* Return bits m to n of x */ +#define GET_BITS(x, m, n) ((((uint32_t)x) << (31 - (n))) >> ((31 - (n)) + (m))) + +/* Bit-banding macros */ +#define BITBAND_SRAM_REF 0x20000000 +#define BITBAND_SRAM_BASE 0x22000000 +#define BITBAND_SRAM(a,b) ((BITBAND_SRAM_BASE + (a-BITBAND_SRAM_REF)*32 + (b*4))) // Convert SRAM address +#define BITBAND_PERI_REF 0x40000000 +#define BITBAND_PERI_BASE 0x42000000 +#define BITBAND_PERI(a,b) ((BITBAND_PERI_BASE + (a-BITBAND_PERI_REF)*32 + (b*4))) // Convert PERI address + +#define COUNTFLAG *((volatile unsigned char*) (BITBAND_PERI(SYSTICK_CSR,2))) + +#define REG_SET(reg, val) (*(volatile uint32_t*)(reg) = (val)) +#define REG_SET_BIT(reg, bit) (*(volatile uint32_t*)(reg) |= BIT(bit)) +#define REG_CLEAR_BIT(reg, bit) (*(volatile uint32_t*)(reg) &= ~BIT(bit)) +#define REG_SET_MASK(reg, mask) (*(volatile uint32_t*)(reg) |= (uint32_t)(mask)) +#define REG_CLEAR_MASK(reg, mask) (*(volatile uint32_t*)(reg) &= (uint32_t)~(mask)) + +#define REG_GET(reg) *(volatile uint32_t*)(reg) + + +#ifdef __cplusplus +extern "C"{ +#endif + +void _fail(const char*, int, const char*); + +#ifdef __cplusplus +} // extern "C" +#endif + + +/* Assert for sanity checks, undefine MAPLE_DEBUG to compile + * out these checks */ +#if MAPLE_DEBUG +#define ASSERT(exp) \ + if (exp) \ + {} \ + else \ + _fail(__FILE__, __LINE__, #exp) +#else +#define ASSERT(exp) (void)((0)) +#endif + +#endif + diff --git a/src/main.cpp b/src/main.cpp new file mode 100644 index 0000000..2007c2f --- /dev/null +++ b/src/main.cpp @@ -0,0 +1,67 @@ +#include "stm32f10x_map.h"
+#include "stm32f10x_lib.h"
+#include "stm32f10x_flash.h"
+#include "stm32f10x_usart.h"
+#include "Serial.h"
+#include "timers.h"
+#include "wiring.h"
+#include "util.h"
+#include "systick.h"
+#include "adc.h"
+#include "gpio.h"
+#include "pwm.h"
+#include "ext_interrupts.h"
+#include "usart.h"
+
+void setup();
+void loop();
+
+int ledPin = 13;
+
+void setup()
+{
+// Serial1.begin(9600);
+// Serial1.println("setup start");
+
+// pinMode(ledPin, OUTPUT);
+ pinMode(1, GPIO_MODE_AF_OUTPUT_PP);
+ pinMode(0, INPUT);
+
+ pinMode(ledPin, OUTPUT);
+
+// usart_init(2);
+
+
+// Serial1.println("setup end");
+}
+
+int toggle = 0;
+
+void loop() {
+ toggle ^= 1;
+ digitalWrite(ledPin, toggle);
+ delay(100);
+}
+
+
+int main(void)
+{
+ init();
+ setup();
+
+ while (1) {
+ loop();
+ }
+ return 0;
+}
+
+
+/* Implemented:
+ * void pinMode(pin, mode)
+ * void digitalWrite(pin, value)
+ * uint32_t digitalRead(pin)
+ * uint32_t analogRead(pin)
+ * void randomSeed(seed)
+ * long random(max)
+ * long random(min, max)
+ * */
diff --git a/src/stm32lib/examples/ADC/3ADCs_DMA/main.c b/src/stm32lib/examples/ADC/3ADCs_DMA/main.c new file mode 100755 index 0000000..0ea0447 --- /dev/null +++ b/src/stm32lib/examples/ADC/3ADCs_DMA/main.c @@ -0,0 +1,318 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define ADC1_DR_Address ((u32)0x4001244C)
+#define ADC3_DR_Address ((u32)0x40013C4C)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ADC_InitTypeDef ADC_InitStructure;
+DMA_InitTypeDef DMA_InitStructure;
+vu16 ADC1ConvertedValue = 0, ADC3ConvertedValue = 0;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* DMA1 channel1 configuration ----------------------------------------------*/
+ DMA_DeInit(DMA1_Channel1);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = ADC1_DR_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)&ADC1ConvertedValue;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = 1;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Disable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA1_Channel1, &DMA_InitStructure);
+ /* Enable DMA1 channel1 */
+ DMA_Cmd(DMA1_Channel1, ENABLE);
+
+ /* DMA2 channel5 configuration ----------------------------------------------*/
+ DMA_DeInit(DMA2_Channel5);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = ADC3_DR_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)&ADC3ConvertedValue;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = 1;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Disable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA2_Channel5, &DMA_InitStructure);
+ /* Enable DMA2 channel5 */
+ DMA_Cmd(DMA2_Channel5, ENABLE);
+
+ /* ADC1 configuration ------------------------------------------------------*/
+ ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
+ ADC_InitStructure.ADC_ScanConvMode = DISABLE;
+ ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
+ ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
+ ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
+ ADC_InitStructure.ADC_NbrOfChannel = 1;
+ ADC_Init(ADC1, &ADC_InitStructure);
+ /* ADC1 regular channels configuration */
+ ADC_RegularChannelConfig(ADC1, ADC_Channel_14, 1, ADC_SampleTime_28Cycles5);
+ /* Enable ADC1 DMA */
+ ADC_DMACmd(ADC1, ENABLE);
+
+ /* ADC2 configuration ------------------------------------------------------*/
+ ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
+ ADC_InitStructure.ADC_ScanConvMode = DISABLE;
+ ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
+ ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
+ ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
+ ADC_InitStructure.ADC_NbrOfChannel = 1;
+ ADC_Init(ADC2, &ADC_InitStructure);
+ /* ADC2 regular channels configuration */
+ ADC_RegularChannelConfig(ADC2, ADC_Channel_13, 1, ADC_SampleTime_28Cycles5);
+ /* Enable ADC2 EOC interupt */
+ ADC_ITConfig(ADC2, ADC_IT_EOC, ENABLE);
+
+ /* ADC3 configuration ------------------------------------------------------*/
+ ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
+ ADC_InitStructure.ADC_ScanConvMode = DISABLE;
+ ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
+ ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
+ ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
+ ADC_InitStructure.ADC_NbrOfChannel = 1;
+ ADC_Init(ADC3, &ADC_InitStructure);
+ /* ADC3 regular channel14 configuration */
+ ADC_RegularChannelConfig(ADC3, ADC_Channel_12, 1, ADC_SampleTime_28Cycles5);
+ /* Enable ADC3 DMA */
+ ADC_DMACmd(ADC3, ENABLE);
+
+ /* Enable ADC1 */
+ ADC_Cmd(ADC1, ENABLE);
+
+ /* Enable ADC1 reset calibaration register */
+ ADC_ResetCalibration(ADC1);
+ /* Check the end of ADC1 reset calibration register */
+ while(ADC_GetResetCalibrationStatus(ADC1));
+
+ /* Start ADC1 calibaration */
+ ADC_StartCalibration(ADC1);
+ /* Check the end of ADC1 calibration */
+ while(ADC_GetCalibrationStatus(ADC1));
+
+ /* Enable ADC2 */
+ ADC_Cmd(ADC2, ENABLE);
+
+ /* Enable ADC2 reset calibaration register */
+ ADC_ResetCalibration(ADC2);
+ /* Check the end of ADC2 reset calibration register */
+ while(ADC_GetResetCalibrationStatus(ADC2));
+
+ /* Start ADC2 calibaration */
+ ADC_StartCalibration(ADC2);
+ /* Check the end of ADC2 calibration */
+ while(ADC_GetCalibrationStatus(ADC2));
+
+ /* Enable ADC3 */
+ ADC_Cmd(ADC3, ENABLE);
+
+ /* Enable ADC3 reset calibaration register */
+ ADC_ResetCalibration(ADC3);
+ /* Check the end of ADC3 reset calibration register */
+ while(ADC_GetResetCalibrationStatus(ADC3));
+
+ /* Start ADC3 calibaration */
+ ADC_StartCalibration(ADC3);
+ /* Check the end of ADC3 calibration */
+ while(ADC_GetCalibrationStatus(ADC3));
+
+ /* Start ADC1 Software Conversion */
+ ADC_SoftwareStartConvCmd(ADC1, ENABLE);
+ /* Start ADC2 Software Conversion */
+ ADC_SoftwareStartConvCmd(ADC2, ENABLE);
+ /* Start ADC3 Software Conversion */
+ ADC_SoftwareStartConvCmd(ADC3, ENABLE);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* ADCCLK = PCLK2/4 */
+ RCC_ADCCLKConfig(RCC_PCLK2_Div4);
+
+ /* PLLCLK = 8MHz * 7 = 56 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_7);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* Enable DMA1 and DMA2 clocks */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1 | RCC_AHBPeriph_DMA2, ENABLE);
+
+ /* Enable ADC1, ADC2, ADC3 and GPIOC clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2 |
+ RCC_APB2Periph_ADC3 | RCC_APB2Periph_GPIOC, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure PC.02, PC.03 and PC.04 (ADC Channel12, ADC Channel13 and
+ ADC Channel14) as analog inputs */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2 | GPIO_Pin_3 | GPIO_Pin_4;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Configure and enable ADC interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = ADC1_2_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/3ADCs_DMA/readme.txt b/src/stm32lib/examples/ADC/3ADCs_DMA/readme.txt new file mode 100755 index 0000000..00fe3e7 --- /dev/null +++ b/src/stm32lib/examples/ADC/3ADCs_DMA/readme.txt @@ -0,0 +1,78 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the 3ADCs DMA example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example describes how to use the 3 ADCs in independant conversions.
+Two of them; ADC1 and ADC3 are transfering continuously converted data using DMA
+while ADC2 converted data are stored using End of conversion interrupt.
+
+ADC1 is configured to converts continuously ADC channel14. Each time an end of
+conversion occurs the DMA1 transfers, in circular mode, the converted data from
+ADC1 DR register to the ADC1_ConvertedValue variable.
+
+ADC2 is configured to converts continuously ADC channel13. Each time an end of
+conversion occurs an end of conversion interrupt is generated and inside the
+interrupt routine the converted data are read from ADC2 DR register and stored
+into the ADC2_ConvertedValue variable.
+
+ADC3 is configured to converts continuously ADC channel12. Each time an end of
+conversion occurs the DMA2 transfers, in circular mode, the converted data from
+ADC3 DR register to the ADC3_ConvertedValue variable.
+
+The ADCs clocks are set to 14 MHz.
+
+The result of ADC1, ADC2 and ADC3 conversion is monitored through the three
+variables: ADC1ConvertedValue, ADC2ConvertedValue and ADC3ConvertedValue.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board and can be
+easily tailored to any other hardware.
+
+ - Connect a variable power supply 0-3.3V to ADC Channel12 mapped on pin PC.02
+ - Connect a variable power supply 0-3.3V to ADC Channel13 mapped on pin PC.03
+ - Connect a variable power supply 0-3.3V to ADC Channel14 mapped on pin PC.04
+ (potentiometer RV1 on STM3210E-EVAL board)
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_adc.c
+ + stm32f10x_dma.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/ADC/3ADCs_DMA/stm32f10x_conf.h b/src/stm32lib/examples/ADC/3ADCs_DMA/stm32f10x_conf.h new file mode 100755 index 0000000..0280527 --- /dev/null +++ b/src/stm32lib/examples/ADC/3ADCs_DMA/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+#define _ADC
+#define _ADC1
+#define _ADC2
+#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/3ADCs_DMA/stm32f10x_it.c b/src/stm32lib/examples/ADC/3ADCs_DMA/stm32f10x_it.c new file mode 100755 index 0000000..764ad60 --- /dev/null +++ b/src/stm32lib/examples/ADC/3ADCs_DMA/stm32f10x_it.c @@ -0,0 +1,814 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+vu16 ADC2ConvertedValue;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+ /* Get injected channel13 converted value */
+ ADC2ConvertedValue = ADC_GetConversionValue(ADC2);
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/3ADCs_DMA/stm32f10x_it.h b/src/stm32lib/examples/ADC/3ADCs_DMA/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/ADC/3ADCs_DMA/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/ADC1_DMA/main.c b/src/stm32lib/examples/ADC/ADC1_DMA/main.c new file mode 100755 index 0000000..f9a09cb --- /dev/null +++ b/src/stm32lib/examples/ADC/ADC1_DMA/main.c @@ -0,0 +1,236 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define ADC1_DR_Address ((u32)0x4001244C)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ADC_InitTypeDef ADC_InitStructure;
+DMA_InitTypeDef DMA_InitStructure;
+vu16 ADCConvertedValue;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* DMA1 channel1 configuration ----------------------------------------------*/
+ DMA_DeInit(DMA1_Channel1);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = ADC1_DR_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)&ADCConvertedValue;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = 1;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Disable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA1_Channel1, &DMA_InitStructure);
+
+ /* Enable DMA1 channel1 */
+ DMA_Cmd(DMA1_Channel1, ENABLE);
+
+ /* ADC1 configuration ------------------------------------------------------*/
+ ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
+ ADC_InitStructure.ADC_ScanConvMode = ENABLE;
+ ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
+ ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
+ ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
+ ADC_InitStructure.ADC_NbrOfChannel = 1;
+ ADC_Init(ADC1, &ADC_InitStructure);
+
+ /* ADC1 regular channel14 configuration */
+ ADC_RegularChannelConfig(ADC1, ADC_Channel_14, 1, ADC_SampleTime_55Cycles5);
+
+ /* Enable ADC1 DMA */
+ ADC_DMACmd(ADC1, ENABLE);
+
+ /* Enable ADC1 */
+ ADC_Cmd(ADC1, ENABLE);
+
+ /* Enable ADC1 reset calibaration register */
+ ADC_ResetCalibration(ADC1);
+ /* Check the end of ADC1 reset calibration register */
+ while(ADC_GetResetCalibrationStatus(ADC1));
+
+ /* Start ADC1 calibaration */
+ ADC_StartCalibration(ADC1);
+ /* Check the end of ADC1 calibration */
+ while(ADC_GetCalibrationStatus(ADC1));
+
+ /* Start ADC1 Software Conversion */
+ ADC_SoftwareStartConvCmd(ADC1, ENABLE);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* ADCCLK = PCLK2/4 */
+ RCC_ADCCLKConfig(RCC_PCLK2_Div4);
+
+ /* PLLCLK = 8MHz * 7 = 56 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_7);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* Enable DMA1 clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+
+ /* Enable ADC1 and GPIOC clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_GPIOC, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure PC.04 (ADC Channel14) as analog input -------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/ADC1_DMA/readme.txt b/src/stm32lib/examples/ADC/ADC1_DMA/readme.txt new file mode 100755 index 0000000..39ebfc6 --- /dev/null +++ b/src/stm32lib/examples/ADC/ADC1_DMA/readme.txt @@ -0,0 +1,60 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the ADC1 DMA example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example describes how to use the ADC1 and DMA to transfer continuously
+converted data from ADC1 to memory.
+The ADC1 is configured to converts continuously ADC channel14.
+Each time an end of conversion occurs the DMA transfers, in circular mode, the
+converted data from ADC1 DR register to the ADC_ConvertedValue variable.
+The ADC1 clock is set to 14 MHz.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+ - Connect a variable power supply 0-3.3V to ADC Channel14 mapped on pin PC.04
+ (potentiometer RV1 on STM3210B-EVAL and STM3210E-EVAL boards)
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_adc.c
+ + stm32f10x_dma.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/ADC/ADC1_DMA/stm32f10x_conf.h b/src/stm32lib/examples/ADC/ADC1_DMA/stm32f10x_conf.h new file mode 100755 index 0000000..f808ae3 --- /dev/null +++ b/src/stm32lib/examples/ADC/ADC1_DMA/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+#define _ADC
+#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/ADC1_DMA/stm32f10x_it.c b/src/stm32lib/examples/ADC/ADC1_DMA/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/ADC/ADC1_DMA/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/ADC1_DMA/stm32f10x_it.h b/src/stm32lib/examples/ADC/ADC1_DMA/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/ADC/ADC1_DMA/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/AnalogWatchdog/main.c b/src/stm32lib/examples/ADC/AnalogWatchdog/main.c new file mode 100755 index 0000000..732d75c --- /dev/null +++ b/src/stm32lib/examples/ADC/AnalogWatchdog/main.c @@ -0,0 +1,234 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ADC_InitTypeDef ADC_InitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* ADC1 Configuration ------------------------------------------------------*/
+ ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
+ ADC_InitStructure.ADC_ScanConvMode = DISABLE;
+ ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
+ ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
+ ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
+ ADC_InitStructure.ADC_NbrOfChannel = 1;
+ ADC_Init(ADC1, &ADC_InitStructure);
+
+ /* ADC1 regular channel14 configuration */
+ ADC_RegularChannelConfig(ADC1, ADC_Channel_14, 1, ADC_SampleTime_13Cycles5);
+
+ /* Configure high and low analog watchdog thresholds */
+ ADC_AnalogWatchdogThresholdsConfig(ADC1, 0x0B00, 0x0300);
+ /* Configure channel14 as the single analog watchdog guarded channel */
+ ADC_AnalogWatchdogSingleChannelConfig(ADC1, ADC_Channel_14);
+ /* Enable analog watchdog on one regular channel */
+ ADC_AnalogWatchdogCmd(ADC1, ADC_AnalogWatchdog_SingleRegEnable);
+
+ /* Enable AWD interupt */
+ ADC_ITConfig(ADC1, ADC_IT_AWD, ENABLE);
+
+ /* Enable ADC1 */
+ ADC_Cmd(ADC1, ENABLE);
+
+ /* Enable ADC1 reset calibaration register */
+ ADC_ResetCalibration(ADC1);
+ /* Check the end of ADC1 reset calibration register */
+ while(ADC_GetResetCalibrationStatus(ADC1));
+
+ /* Start ADC1 calibaration */
+ ADC_StartCalibration(ADC1);
+ /* Check the end of ADC1 calibration */
+ while(ADC_GetCalibrationStatus(ADC1));
+
+ /* Start ADC1 Software Conversion */
+ ADC_SoftwareStartConvCmd(ADC1, ENABLE);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* ADCCLK = PCLK2/4 */
+ RCC_ADCCLKConfig(RCC_PCLK2_Div4);
+
+ /* PLLCLK = 8MHz * 7 = 56 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_7);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* Enable ADC1 and GPIO_LED clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_GPIO_LED, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure GOIO_LED pin 6 as output push-pull ----------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ /* Configure PC.04 (ADC Channel14) as analog input -------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures NVIC and Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Configure and enable ADC interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = ADC1_2_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/AnalogWatchdog/platform_config.h b/src/stm32lib/examples/ADC/AnalogWatchdog/platform_config.h new file mode 100755 index 0000000..0bc5169 --- /dev/null +++ b/src/stm32lib/examples/ADC/AnalogWatchdog/platform_config.h @@ -0,0 +1,44 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/AnalogWatchdog/readme.txt b/src/stm32lib/examples/ADC/AnalogWatchdog/readme.txt new file mode 100755 index 0000000..c550b53 --- /dev/null +++ b/src/stm32lib/examples/ADC/AnalogWatchdog/readme.txt @@ -0,0 +1,73 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the ADC analog watchdog example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example describes how to use the ADC analog watchdog to guard continuously
+an ADC channel.
+The ADC1 is configured to convert continuously ADC channel14. The analog watchdog
+is configured and enabled to guard a single regular channel.
+Each time the channel14 converted value exceed programmed analog watchdog high
+threshold (value 0x0B00) or goes down analog watchdog low threshold (value 0x0300)
+an AWD interrupt is generated and the output pin connected to LED1 is toggled. The
+LED will bright as long as the AWD interrupt is generated which means that the
+converted value of regular ADC channel14 is outside the range limited by high and
+low analog watchdog thresholds.
+The ADC1 clock is set to 14 MHz.
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1 led connected to PC.06 pin
+
+ + STM3210E-EVAL
+ - Use LD1 led connected to PF.06 pin
+
+ - Connect a variable power supply 0-3.3V to ADC Channel14 mapped on pin PC.04
+ (potentiometer RV1 on STM3210B-EVAL and STM3210E-EVAL boards)
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_adc.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/ADC/AnalogWatchdog/stm32f10x_conf.h b/src/stm32lib/examples/ADC/AnalogWatchdog/stm32f10x_conf.h new file mode 100755 index 0000000..dac090e --- /dev/null +++ b/src/stm32lib/examples/ADC/AnalogWatchdog/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+#define _ADC
+#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/AnalogWatchdog/stm32f10x_it.c b/src/stm32lib/examples/ADC/AnalogWatchdog/stm32f10x_it.c new file mode 100755 index 0000000..c73d218 --- /dev/null +++ b/src/stm32lib/examples/ADC/AnalogWatchdog/stm32f10x_it.c @@ -0,0 +1,817 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+ /* Toggle LED */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_6, Bit_SET);
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_6, Bit_RESET);
+
+ /* Clear ADC1 AWD pending interrupt bit */
+ ADC_ClearITPendingBit(ADC1, ADC_IT_AWD);
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/AnalogWatchdog/stm32f10x_it.h b/src/stm32lib/examples/ADC/AnalogWatchdog/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/ADC/AnalogWatchdog/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/ExtLinesTrigger/main.c b/src/stm32lib/examples/ADC/ExtLinesTrigger/main.c new file mode 100755 index 0000000..9ed1551 --- /dev/null +++ b/src/stm32lib/examples/ADC/ExtLinesTrigger/main.c @@ -0,0 +1,316 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define ADC1_DR_Address ((u32)0x4001244C)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ADC_InitTypeDef ADC_InitStructure;
+DMA_InitTypeDef DMA_InitStructure;
+vu16 ADC_RegularConvertedValueTab[64], ADC_InjectedConvertedValueTab[32];
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+void EXTI_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* EXTI configuration ------------------------------------------------------*/
+ EXTI_Configuration();
+
+ /* DMA1 channel1 configuration ----------------------------------------------*/
+ DMA_DeInit(DMA1_Channel1);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = ADC1_DR_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)ADC_RegularConvertedValueTab;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = 64;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA1_Channel1, &DMA_InitStructure);
+
+ /* Enable DMA1 channel1 */
+ DMA_Cmd(DMA1_Channel1, ENABLE);
+
+ /* ADC1 configuration ------------------------------------------------------*/
+ ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
+ ADC_InitStructure.ADC_ScanConvMode = ENABLE;
+ ADC_InitStructure.ADC_ContinuousConvMode = DISABLE;
+ ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO;
+ ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
+ ADC_InitStructure.ADC_NbrOfChannel = 2;
+ ADC_Init(ADC1, &ADC_InitStructure);
+
+ /* ADC1 regular channels configuration */
+ ADC_RegularChannelConfig(ADC1, ADC_Channel_4, 1, ADC_SampleTime_28Cycles5);
+ ADC_RegularChannelConfig(ADC1, ADC_Channel_14, 2, ADC_SampleTime_28Cycles5);
+
+ /* Regular discontinuous mode channel number configuration */
+ ADC_DiscModeChannelCountConfig(ADC1, 1);
+ /* Enable regular discontinuous mode */
+ ADC_DiscModeCmd(ADC1, ENABLE);
+
+ /* Enable ADC1 external trigger conversion */
+ ADC_ExternalTrigConvCmd(ADC1, ENABLE);
+
+ /* Set injected sequencer length */
+ ADC_InjectedSequencerLengthConfig(ADC1, 2);
+ /* ADC1 injected channel configuration */
+ ADC_InjectedChannelConfig(ADC1, ADC_Channel_11, 1, ADC_SampleTime_28Cycles5);
+ ADC_InjectedChannelConfig(ADC1, ADC_Channel_12, 2, ADC_SampleTime_28Cycles5);
+ /* ADC1 injected external trigger configuration */
+ ADC_ExternalTrigInjectedConvConfig(ADC1, ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4);
+ /* Enable ADC1 injected external trigger conversion */
+ ADC_ExternalTrigInjectedConvCmd(ADC1, ENABLE);
+
+ /* Enable JEOC interupt */
+ ADC_ITConfig(ADC1, ADC_IT_JEOC, ENABLE);
+
+ /* Enable ADC1 DMA */
+ ADC_DMACmd(ADC1, ENABLE);
+
+ /* Enable ADC1 */
+ ADC_Cmd(ADC1, ENABLE);
+
+ /* Enable ADC1 reset calibaration register */
+ ADC_ResetCalibration(ADC1);
+ /* Check the end of ADC1 reset calibration register */
+ while(ADC_GetResetCalibrationStatus(ADC1));
+
+ /* Start ADC1 calibaration */
+ ADC_StartCalibration(ADC1);
+ /* Check the end of ADC1 calibration */
+ while(ADC_GetCalibrationStatus(ADC1));
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* ADCCLK = PCLK2/4 */
+ RCC_ADCCLKConfig(RCC_PCLK2_Div4);
+
+ /* PLLCLK = 8MHz * 7 = 56 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_7);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* Enable DMA1 clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+
+ /* Enable GPIOs and ADC1 clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOC |
+ RCC_APB2Periph_GPIOE | RCC_APB2Periph_AFIO |
+ RCC_APB2Periph_ADC1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : EXTI_Configuration
+* Description : Configures the different EXTI lines.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_Configuration(void)
+{
+ EXTI_InitTypeDef EXTI_InitStructure;
+
+ /* Select the EXTI Line11 the GPIO pin source */
+ GPIO_EXTILineConfig(GPIO_PortSourceGPIOE, GPIO_PinSource11);
+ /* EXTI line11 configuration -----------------------------------------------*/
+ EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Event;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
+ EXTI_InitStructure.EXTI_Line = EXTI_Line11;
+ EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+ EXTI_Init(&EXTI_InitStructure);
+
+ /* Select the EXTI Line15 the GPIO pin source */
+ GPIO_EXTILineConfig(GPIO_PortSourceGPIOE, GPIO_PinSource15);
+ /* EXTI line15 configuration -----------------------------------------------*/
+ EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Event;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
+ EXTI_InitStructure.EXTI_Line = EXTI_Line15;
+ EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+ EXTI_Init(&EXTI_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure PC.01, PC.02 and PC.04 (ADC Channel11, Channel12 and Channel14)
+ as analog input -----------------------------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_4;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+
+ /* Configure PA.04 (ADC Channel4) as analog input --------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure EXTI line11 ---------------------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOE, &GPIO_InitStructure);
+
+ /* Configure EXTI line15 ---------------------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_15;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOE, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures NVIC and Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Configure and enable ADC interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = ADC1_2_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/ExtLinesTrigger/readme.txt b/src/stm32lib/examples/ADC/ExtLinesTrigger/readme.txt new file mode 100755 index 0000000..ecb06f5 --- /dev/null +++ b/src/stm32lib/examples/ADC/ExtLinesTrigger/readme.txt @@ -0,0 +1,80 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the ADC external lines trigger example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example describes how to trigger ADC regular and injected groups channels
+conversion using two external line events. Discontinuous mode is enabled for regular
+group channel conversion and configured to convert one regular channel on each
+external trigger.
+
+ADC1 is configured to start regular group channel conversion on EXTI11 event.
+On detection of the first rising edge on PE.11 pin, the conversion of the first regular
+channel (ADC channel4) is done and its converted value is transfered by DMA to
+ADC_RegularConvertedValueTab table. On the following edge detection, the second
+regular channel (ADC channel14) is automatically converted and its converted value
+is stored by DMA in the same table. The number of transmitted data by DMA, in this
+example is limited to 64 data.
+
+The procedure is repeated for both regular channels on each EXTI11 event.
+ADC1 is configured to start injected group channel conversion on EXTI15 event.
+On detection of the first rising edge on PE.15 pin all selected injected channels, which
+are two in this example (ADC channel11 and channel12), are converted and an interrupt
+is generated on JEOC flag rising at the end of all injected channels conversion.
+Both injected channels converted results are stored in ADC_InjectedConvertedValueTab
+table inside the interrupt routine.
+The procedure is repeated for injected channels on each EXTI15 event.
+The ADC1 clock is set to 14 MHz.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+ - Connect a known voltage, between 0-3.3V, to ADC Channel14 mapped on pin PC.04
+ (potentiometer RV1 on STM3210B-EVAL and STM3210E-EVAL boards), ADC Channel4 mapped
+ on pin PA.04, ADC Channel11 mapped on pin PC.01 and ADC Channel12 mapped on pin PC.02.
+ - Connect a push-button to pin PE.11 (EXTI Line11) and another push-button to
+ pin PE.15 (EXTI Line15).
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_adc.c
+ + stm32f10x_dma.c
+ + stm32f10x_exti.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/ADC/ExtLinesTrigger/stm32f10x_conf.h b/src/stm32lib/examples/ADC/ExtLinesTrigger/stm32f10x_conf.h new file mode 100755 index 0000000..1bfe46f --- /dev/null +++ b/src/stm32lib/examples/ADC/ExtLinesTrigger/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+#define _ADC
+#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/ExtLinesTrigger/stm32f10x_it.c b/src/stm32lib/examples/ADC/ExtLinesTrigger/stm32f10x_it.c new file mode 100755 index 0000000..23ef0da --- /dev/null +++ b/src/stm32lib/examples/ADC/ExtLinesTrigger/stm32f10x_it.c @@ -0,0 +1,824 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+extern vu16 ADC_InjectedConvertedValueTab[32];
+vu32 Index = 0;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+ /* Clear ADC1 JEOC pending interrupt bit */
+ ADC_ClearITPendingBit(ADC1, ADC_IT_JEOC);
+
+ /* Get injected channel10 and channel11 converted value */
+ ADC_InjectedConvertedValueTab[Index++] = ADC_GetInjectedConversionValue(ADC1, ADC_InjectedChannel_1);
+ ADC_InjectedConvertedValueTab[Index++] = ADC_GetInjectedConversionValue(ADC1, ADC_InjectedChannel_2);
+
+ if (Index == 32)
+ {
+ Index = 0;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/ExtLinesTrigger/stm32f10x_it.h b/src/stm32lib/examples/ADC/ExtLinesTrigger/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/ADC/ExtLinesTrigger/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/RegSimul_DualMode/main.c b/src/stm32lib/examples/ADC/RegSimul_DualMode/main.c new file mode 100755 index 0000000..b00bf71 --- /dev/null +++ b/src/stm32lib/examples/ADC/RegSimul_DualMode/main.c @@ -0,0 +1,270 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define ADC1_DR_Address ((u32)0x4001244C)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ADC_InitTypeDef ADC_InitStructure;
+DMA_InitTypeDef DMA_InitStructure;
+vu32 ADC_DualConvertedValueTab[16];
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* DMA1 channel1 configuration ----------------------------------------------*/
+ DMA_DeInit(DMA1_Channel1);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)ADC1_DR_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)ADC_DualConvertedValueTab;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = 16;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA1_Channel1, &DMA_InitStructure);
+ /* Enable DMA1 Channel1 */
+ DMA_Cmd(DMA1_Channel1, ENABLE);
+
+ /* ADC1 configuration ------------------------------------------------------*/
+ ADC_InitStructure.ADC_Mode = ADC_Mode_RegSimult;
+ ADC_InitStructure.ADC_ScanConvMode = ENABLE;
+ ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
+ ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
+ ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
+ ADC_InitStructure.ADC_NbrOfChannel = 2;
+ ADC_Init(ADC1, &ADC_InitStructure);
+ /* ADC1 regular channels configuration */
+ ADC_RegularChannelConfig(ADC1, ADC_Channel_14, 1, ADC_SampleTime_239Cycles5);
+ ADC_RegularChannelConfig(ADC1, ADC_Channel_17, 2, ADC_SampleTime_239Cycles5);
+ /* Enable ADC1 DMA */
+ ADC_DMACmd(ADC1, ENABLE);
+
+ /* ADC2 configuration ------------------------------------------------------*/
+ ADC_InitStructure.ADC_Mode = ADC_Mode_RegSimult;
+ ADC_InitStructure.ADC_ScanConvMode = ENABLE;
+ ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
+ ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
+ ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
+ ADC_InitStructure.ADC_NbrOfChannel = 2;
+ ADC_Init(ADC2, &ADC_InitStructure);
+ /* ADC2 regular channels configuration */
+ ADC_RegularChannelConfig(ADC2, ADC_Channel_11, 1, ADC_SampleTime_239Cycles5);
+ ADC_RegularChannelConfig(ADC2, ADC_Channel_12, 2, ADC_SampleTime_239Cycles5);
+ /* Enable ADC2 external trigger conversion */
+ ADC_ExternalTrigConvCmd(ADC2, ENABLE);
+
+ /* Enable ADC1 */
+ ADC_Cmd(ADC1, ENABLE);
+ /* Enable Vrefint channel17 */
+ ADC_TempSensorVrefintCmd(ENABLE);
+
+ /* Enable ADC1 reset calibaration register */
+ ADC_ResetCalibration(ADC1);
+ /* Check the end of ADC1 reset calibration register */
+ while(ADC_GetResetCalibrationStatus(ADC1));
+
+ /* Start ADC1 calibaration */
+ ADC_StartCalibration(ADC1);
+ /* Check the end of ADC1 calibration */
+ while(ADC_GetCalibrationStatus(ADC1));
+
+ /* Enable ADC2 */
+ ADC_Cmd(ADC2, ENABLE);
+
+ /* Enable ADC2 reset calibaration register */
+ ADC_ResetCalibration(ADC2);
+ /* Check the end of ADC2 reset calibration register */
+ while(ADC_GetResetCalibrationStatus(ADC2));
+
+ /* Start ADC2 calibaration */
+ ADC_StartCalibration(ADC2);
+ /* Check the end of ADC2 calibration */
+ while(ADC_GetCalibrationStatus(ADC2));
+
+ /* Start ADC1 Software Conversion */
+ ADC_SoftwareStartConvCmd(ADC1, ENABLE);
+
+ /* Test on DMA1 channel1 transfer complete flag */
+ while(!DMA_GetFlagStatus(DMA1_FLAG_TC1));
+ /* Clear DMA1 channel1 transfer complete flag */
+ DMA_ClearFlag(DMA1_FLAG_TC1);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* ADCCLK = PCLK2/4 */
+ RCC_ADCCLKConfig(RCC_PCLK2_Div4);
+
+ /* PLLCLK = 8MHz * 7 = 56 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_7);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* Enable DMA1 clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+
+ /* Enable ADC1, ADC2 and GPIOC clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2 |
+ RCC_APB2Periph_GPIOC, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure PC.01, PC.02 and PC.04 (ADC Channel11, Channel12 and Channel14)
+ as analog input ----------------------------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_4;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/RegSimul_DualMode/readme.txt b/src/stm32lib/examples/ADC/RegSimul_DualMode/readme.txt new file mode 100755 index 0000000..ded3195 --- /dev/null +++ b/src/stm32lib/examples/ADC/RegSimul_DualMode/readme.txt @@ -0,0 +1,71 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the ADC regular simultaneous dual mode Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example describes how to use ADC1 and ADC2 in regular simultaneous dual mode.
+ADC1 is configured to convert channel14 and channel17 regular channels continuously.
+ADC2 is configured to convert channel11 and channel12 regular channels continuously.
+The connection between internal Vref and channel17 is enabled for ADC1.
+
+Once the regular channels conversion is started by software, channel14 is converted
+on ADC1 and channel11 is converted on ADC2 on the same time. The 32bits conversion
+result is then stored on ADC1 DR register. The DMA will transfer this data which
+will be stored ADC_DualConvertedValueTab table. Consecutively to those conversion,
+channel17 is converted on ADC1 and channel12 on ADC2. The combined conversion
+result is also transfered by DMA to the same destination buffer.
+
+The same procedure is repeated until the specified number of data to be transfered
+by DMA is reached.
+
+The ADC1 clock is set to 14 MHz.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+ - Connect a known voltage, between 0-3.3V, to ADC Channel14 mapped on pin PC.04
+ (potentiometer RV1 on STM3210B-EVAL and STM3210E-EVAL boards),ADC Channel11 mapped
+ on pin PC.01 and ADC Channel12 mapped on pin PC.02.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_adc.c
+ + stm32f10x_dma.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/ADC/RegSimul_DualMode/stm32f10x_conf.h b/src/stm32lib/examples/ADC/RegSimul_DualMode/stm32f10x_conf.h new file mode 100755 index 0000000..39d0a20 --- /dev/null +++ b/src/stm32lib/examples/ADC/RegSimul_DualMode/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+#define _ADC
+#define _ADC1
+#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/RegSimul_DualMode/stm32f10x_it.c b/src/stm32lib/examples/ADC/RegSimul_DualMode/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/ADC/RegSimul_DualMode/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/RegSimul_DualMode/stm32f10x_it.h b/src/stm32lib/examples/ADC/RegSimul_DualMode/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/ADC/RegSimul_DualMode/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/main.c b/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/main.c new file mode 100755 index 0000000..8133157 --- /dev/null +++ b/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/main.c @@ -0,0 +1,300 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define ADC1_DR_Address ((u32)0x4001244C)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ADC_InitTypeDef ADC_InitStructure;
+DMA_InitTypeDef DMA_InitStructure;
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+vu16 ADC_RegularConvertedValueTab[32], ADC_InjectedConvertedValueTab[32];
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* TIM1 configuration ------------------------------------------------------*/
+ /* Time Base configuration */
+ TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
+ TIM_TimeBaseStructure.TIM_Period = 0xFF;
+ TIM_TimeBaseStructure.TIM_Prescaler = 0x4;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0x0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseInit(TIM1, &TIM_TimeBaseStructure);
+ /* TIM1 channel1 configuration in PWM mode */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = 0x7F;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low;
+ TIM_OC1Init(TIM1, &TIM_OCInitStructure);
+
+ /* DMA1 Channel1 Configuration ----------------------------------------------*/
+ DMA_DeInit(DMA1_Channel1);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = ADC1_DR_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)ADC_RegularConvertedValueTab;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = 32;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA1_Channel1, &DMA_InitStructure);
+
+ /* Enable DMA1 channel1 */
+ DMA_Cmd(DMA1_Channel1, ENABLE);
+
+ /* ADC1 configuration ------------------------------------------------------*/
+ ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
+ ADC_InitStructure.ADC_ScanConvMode = DISABLE;
+ ADC_InitStructure.ADC_ContinuousConvMode = DISABLE;
+ ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1;
+ ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
+ ADC_InitStructure.ADC_NbrOfChannel = 1;
+ ADC_Init(ADC1, &ADC_InitStructure);
+
+ /* ADC1 regular channel14 configuration */
+ ADC_RegularChannelConfig(ADC1, ADC_Channel_14, 1, ADC_SampleTime_13Cycles5);
+
+ /* Set injected sequencer length */
+ ADC_InjectedSequencerLengthConfig(ADC1, 1);
+ /* ADC1 injected channel Configuration */
+ ADC_InjectedChannelConfig(ADC1, ADC_Channel_11, 1, ADC_SampleTime_71Cycles5);
+ /* ADC1 injected external trigger configuration */
+ ADC_ExternalTrigInjectedConvConfig(ADC1, ADC_ExternalTrigInjecConv_None);
+
+ /* Enable automatic injected conversion start after regular one */
+ ADC_AutoInjectedConvCmd(ADC1, ENABLE);
+
+ /* Enable ADC1 DMA */
+ ADC_DMACmd(ADC1, ENABLE);
+
+ /* Enable ADC1 external trigger */
+ ADC_ExternalTrigConvCmd(ADC1, ENABLE);
+
+ /* Enable JEOC interupt */
+ ADC_ITConfig(ADC1, ADC_IT_JEOC, ENABLE);
+
+ /* Enable ADC1 */
+ ADC_Cmd(ADC1, ENABLE);
+
+ /* Enable ADC1 reset calibaration register */
+ ADC_ResetCalibration(ADC1);
+ /* Check the end of ADC1 reset calibration register */
+ while(ADC_GetResetCalibrationStatus(ADC1));
+
+ /* Start ADC1 calibaration */
+ ADC_StartCalibration(ADC1);
+ /* Check the end of ADC1 calibration */
+ while(ADC_GetCalibrationStatus(ADC1));
+
+ /* TIM1 counter enable */
+ TIM_Cmd(TIM1, ENABLE);
+ /* TIM1 main Output Enable */
+ TIM_CtrlPWMOutputs(TIM1, ENABLE);
+
+ /* Test on channel1 transfer complete flag */
+ while(!DMA_GetFlagStatus(DMA1_FLAG_TC1));
+ /* Clear channel1 transfer complete flag */
+ DMA_ClearFlag(DMA1_FLAG_TC1);
+
+ /* TIM1 counter disable */
+ TIM_Cmd(TIM1, DISABLE);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* ADCCLK = PCLK2/4 */
+ RCC_ADCCLKConfig(RCC_PCLK2_Div4);
+
+ /* PLLCLK = 8MHz * 7 = 56 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_7);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* Enable DMA1 clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+
+ /* Enable GPIOA, GPIOC, ADC1 and TIM1 clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOC |
+ RCC_APB2Periph_ADC1 | RCC_APB2Periph_TIM1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure TIM1_CH1 (PA8) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure PC.06 as output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+
+ /* Configure PC.01 and PC.04 (ADC Channel11 and Channel14) as analog input */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1 | GPIO_Pin_4;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures NVIC and Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Enable ADC1_2 IRQChannel */
+ NVIC_InitStructure.NVIC_IRQChannel = ADC1_2_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/readme.txt b/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/readme.txt new file mode 100755 index 0000000..6e90439 --- /dev/null +++ b/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/readme.txt @@ -0,0 +1,73 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the ADC TIM trigger and auto-injection Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example describes how to convert ADC regular group channels continuously using
+TIM1 external trigger and injected group channels using the auto-injected feature.
+
+ADC1 is configured to convert on each TIM1 capture compare event ADC channel14.
+Each time an end of regular conversion occurs the DMA transfers, the converted data
+from ADC1 DR register to the ADC_RegularConvertedValueTab table.
+Enabling the auto-injected feature, allows to convert automatically the injected
+channel ADC channel11 after the end of the regular channel14. An ADC interrupt is
+generated then by JEOC flag at the end of the injected channel conversion and in
+the interrupt routine the result is stored in the ADC_InjectedConvertedValueTab table.
+The procedure is repeated 32 times then the TIM1 peripheral is disabled and thus,
+no conversion will be done neither regular or injected.
+TIM1 start conversion triggers can be visualized on oscilloscope on PA.08 and at the
+same time the toggle of pin PC.06 which indicates the automatic auto-injection conversion.
+The ADC1 clock is set to 14 MHz.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+ - Connect a known voltage, between 0-3.3V, to ADC Channel14 mapped on pin PC.04
+ (potentiometer RV1 on STM3210B-EVAL and STM3210E-EVAL boards) and ADC Channel11
+ mapped on pin PC.01
+ - Connect PA.08 and PC.06 pins to an oscilloscope
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_adc.c
+ + stm32f10x_dma.c
+ + stm32f10x_tim.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/stm32f10x_conf.h b/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/stm32f10x_conf.h new file mode 100755 index 0000000..28b4413 --- /dev/null +++ b/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+#define _ADC
+#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/stm32f10x_it.c b/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/stm32f10x_it.c new file mode 100755 index 0000000..727473e --- /dev/null +++ b/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/stm32f10x_it.c @@ -0,0 +1,821 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+extern vu16 ADC_InjectedConvertedValueTab[32];
+vu32 Index;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+ /* Set PC.06 pin */
+ GPIO_WriteBit(GPIOC, GPIO_Pin_6, Bit_SET);
+ /* Get injected channel11 converted value */
+ ADC_InjectedConvertedValueTab[Index++] = ADC_GetInjectedConversionValue(ADC1, ADC_InjectedChannel_1);
+ /* Clear ADC1 JEOC pending interrupt bit */
+ ADC_ClearITPendingBit(ADC1, ADC_IT_JEOC);
+ /* Reset PC.06 pin */
+ GPIO_WriteBit(GPIOC, GPIO_Pin_6, Bit_RESET);
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/stm32f10x_it.h b/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/ADC/TIMTrigger_AutoInjection/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/BKP/Backup_Data/main.c b/src/stm32lib/examples/BKP/Backup_Data/main.c new file mode 100755 index 0000000..83335e0 --- /dev/null +++ b/src/stm32lib/examples/BKP/Backup_Data/main.c @@ -0,0 +1,272 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+
+#ifdef USE_STM3210B_EVAL
+u16 BKPDataReg[BKP_DR_NUMBER] =
+ {
+ BKP_DR1, BKP_DR2, BKP_DR3, BKP_DR4, BKP_DR5, BKP_DR6, BKP_DR7, BKP_DR8,
+ BKP_DR9, BKP_DR10
+ };
+#elif defined USE_STM3210E_EVAL
+u16 BKPDataReg[BKP_DR_NUMBER] =
+ {
+ BKP_DR1, BKP_DR2, BKP_DR3, BKP_DR4, BKP_DR5, BKP_DR6, BKP_DR7, BKP_DR8,
+ BKP_DR9, BKP_DR10, BKP_DR11, BKP_DR12, BKP_DR13, BKP_DR14, BKP_DR15, BKP_DR16,
+ BKP_DR17, BKP_DR18, BKP_DR19, BKP_DR20, BKP_DR21, BKP_DR22, BKP_DR23, BKP_DR24,
+ BKP_DR25, BKP_DR26, BKP_DR27, BKP_DR28, BKP_DR29, BKP_DR30, BKP_DR31, BKP_DR32,
+ BKP_DR33, BKP_DR34, BKP_DR35, BKP_DR36, BKP_DR37, BKP_DR38, BKP_DR39, BKP_DR40,
+ BKP_DR41, BKP_DR42
+ };
+#endif /* USE_STM3210B_EVAL */
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+void WriteToBackupReg(u16 FirstBackupData);
+u8 CheckBackupReg(u16 FirstBackupData);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* GPIO configuration */
+ GPIO_Configuration();
+
+ /* Enable PWR and BKP clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE);
+
+ /* Enable write access to Backup domain */
+ PWR_BackupAccessCmd(ENABLE);
+
+ /* Clear Tamper pin Event(TE) pending flag */
+ BKP_ClearFlag();
+
+ /* Check if the Power On Reset flag is set */
+ if(RCC_GetFlagStatus(RCC_FLAG_PORRST) != RESET)
+ {
+ /* Clear reset flags */
+ RCC_ClearFlag();
+
+ /* Turn on led connected to GPIO_LED Pin8 */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_8);
+
+ /* Check if Backup data registers are programmed */
+ if(CheckBackupReg(0x3210) == 0x00)
+ { /* Backup data registers values are correct */
+
+ /* Turn on led connected to GPIO_LED Pin6 */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_6);
+ }
+ else
+ { /* Backup data registers values are not correct or they are not yet
+ programmed (when the first time the program is executed) */
+
+ /* Write data to Backup data registers */
+ WriteToBackupReg(0x3210);
+
+ /* Turn on led connected to GPIO_LED Pin7 */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_7);
+ }
+ }
+
+ /* Turn on led connected to GPIO_LED Pin9 */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_9);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable GPIO_LED clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_LED, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure GPIO_LED Pin 6, Pin 7, Pin 8 and Pin 9 as Output push-pull ----*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures NVIC and Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/*******************************************************************************
+* Function Name : WriteToBackupReg
+* Description : Writes data Backup DRx registers.
+* Input : FirstBackupData: data to be written to Backup data registers.
+* Output : None
+* Return : None
+*******************************************************************************/
+void WriteToBackupReg(u16 FirstBackupData)
+{
+ u32 index = 0;
+
+ for (index = 0; index < BKP_DR_NUMBER; index++)
+ {
+ BKP_WriteBackupRegister(BKPDataReg[index], FirstBackupData + (index * 0x5A));
+ }
+}
+
+/*******************************************************************************
+* Function Name : CheckBackupReg
+* Description : Checks if the Backup DRx registers values are correct or not.
+* Input : FirstBackupData: data to be compared with Backup data registers.
+* Output : None
+* Return : - 0: All Backup DRx registers values are correct
+* - Value different from 0: Number of the first Backup register
+* which value is not correct
+*******************************************************************************/
+u8 CheckBackupReg(u16 FirstBackupData)
+{
+ u32 index = 0;
+
+ for (index = 0; index < BKP_DR_NUMBER; index++)
+ {
+ if (BKP_ReadBackupRegister(BKPDataReg[index]) != (FirstBackupData + (index * 0x5A)))
+ {
+ return (index + 1);
+ }
+ }
+
+ return 0;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/BKP/Backup_Data/platform_config.h b/src/stm32lib/examples/BKP/Backup_Data/platform_config.h new file mode 100755 index 0000000..3b3f4c0 --- /dev/null +++ b/src/stm32lib/examples/BKP/Backup_Data/platform_config.h @@ -0,0 +1,46 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+ #define BKP_DR_NUMBER 10
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+ #define BKP_DR_NUMBER 42
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/BKP/Backup_Data/readme.txt b/src/stm32lib/examples/BKP/Backup_Data/readme.txt new file mode 100755 index 0000000..2f60bbf --- /dev/null +++ b/src/stm32lib/examples/BKP/Backup_Data/readme.txt @@ -0,0 +1,87 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the BKP Backup_Data Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to store user data in the Backup data registers.
+As the Backup (BKP) domain still powered by VBAT when VDD is switched off, its
+contents are not lost if a battery is connected to VBAT pin.
+
+The program behaves as follows:
+1. After startup the program checks if the board has been powered up. If yes,
+the values in the BKP data registers are checked:
+ – if a battery is connected to the VBAT pin, the values in the BKP data registers
+ are retained
+ – if no battery is connected to the VBAT pin, the values in the BKP data registers
+ are lost
+2. After an external reset, the BKP data registers’ contents are not checked.
+
+Four LEDs connected to the GPIO_LED Pin6 (LD1), Pin7 (LD2), Pin8 (LD3) and Pin9 (LD4)
+are used to monitor the system state as follows:
+1. LD3 on / LD1 on: a Power On Reset occurred and the values in the BKP data
+ registers are correct
+2. LD3 on / LD2 on: a Power On Reset occurred and the values in the BKP data
+ registers are not correct or they have not yet been programmed (if it is the
+ first time the program is executed)
+3. LD3 off / LD1 off / LD2 off: no Power On Reset occurred
+4. LD4 on: program running
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+main.h Header for main.c
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PC.06, PC.07, PC.08
+ and PC.09 pins
+ - Use 3V battery on VBAT pin (set jumper JP11 in position 1-2)
+
+ + STM3210E-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PF.06, PF0.7, PF.08
+ and PF.09 pins
+ - Use 3V battery on VBAT pin (set jumper JP1 in position 1-2)
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_pwr.c
+ + stm32f10x_bkp.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example in standalone mode (without debugger connection)
+- Power on/off the board and check that the BKP contents are not lost
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/BKP/Backup_Data/stm32f10x_conf.h b/src/stm32lib/examples/BKP/Backup_Data/stm32f10x_conf.h new file mode 100755 index 0000000..f0e9f13 --- /dev/null +++ b/src/stm32lib/examples/BKP/Backup_Data/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz */
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/BKP/Backup_Data/stm32f10x_it.c b/src/stm32lib/examples/BKP/Backup_Data/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/BKP/Backup_Data/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/BKP/Backup_Data/stm32f10x_it.h b/src/stm32lib/examples/BKP/Backup_Data/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/BKP/Backup_Data/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/BKP/Tamper/main.c b/src/stm32lib/examples/BKP/Tamper/main.c new file mode 100755 index 0000000..c541e4d --- /dev/null +++ b/src/stm32lib/examples/BKP/Tamper/main.c @@ -0,0 +1,301 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+
+#ifdef USE_STM3210B_EVAL
+u16 BKPDataReg[BKP_DR_NUMBER] =
+ {
+ BKP_DR1, BKP_DR2, BKP_DR3, BKP_DR4, BKP_DR5, BKP_DR6, BKP_DR7, BKP_DR8,
+ BKP_DR9, BKP_DR10
+ };
+#elif defined USE_STM3210E_EVAL
+u16 BKPDataReg[BKP_DR_NUMBER] =
+ {
+ BKP_DR1, BKP_DR2, BKP_DR3, BKP_DR4, BKP_DR5, BKP_DR6, BKP_DR7, BKP_DR8,
+ BKP_DR9, BKP_DR10, BKP_DR11, BKP_DR12, BKP_DR13, BKP_DR14, BKP_DR15, BKP_DR16,
+ BKP_DR17, BKP_DR18, BKP_DR19, BKP_DR20, BKP_DR21, BKP_DR22, BKP_DR23, BKP_DR24,
+ BKP_DR25, BKP_DR26, BKP_DR27, BKP_DR28, BKP_DR29, BKP_DR30, BKP_DR31, BKP_DR32,
+ BKP_DR33, BKP_DR34, BKP_DR35, BKP_DR36, BKP_DR37, BKP_DR38, BKP_DR39, BKP_DR40,
+ BKP_DR41, BKP_DR42
+ };
+#endif /* USE_STM3210B_EVAL */
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+void WriteToBackupReg(u16 FirstBackupData);
+u32 CheckBackupReg(u16 FirstBackupData);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* GPIO configuration */
+ GPIO_Configuration();
+
+ /* Enable PWR and BKP clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE);
+
+ /* Enable write access to Backup domain */
+ PWR_BackupAccessCmd(ENABLE);
+
+ /* Clear Tamper pin Event(TE) pending flag */
+ BKP_ClearFlag();
+
+ /* Tamper pin active on low level */
+ BKP_TamperPinLevelConfig(BKP_TamperPinLevel_Low);
+
+ /* Enable Tamper interrupt */
+ BKP_ITConfig(ENABLE);
+
+ /* Enable Tamper pin */
+ BKP_TamperPinCmd(ENABLE);
+
+ /* Write data to Backup DRx registers */
+ WriteToBackupReg(0xA53C);
+ /* Check if the written data are correct */
+ if(CheckBackupReg(0xA53C) == 0x00)
+ {
+ /* Turn on led connected to GPIO_LED Pin6 */
+ GPIO_Write(GPIO_LED, GPIO_Pin_6);
+ }
+ else
+ {
+ /* Turn on led connected to GPIO_LED Pin7 */
+ GPIO_Write(GPIO_LED, GPIO_Pin_7);
+ }
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable GPIO_LED clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_LED, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure GPIO_LED Pin 6, Pin 7, Pin 8 and Pin 9 as Output push-pull ----*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures NVIC and Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Enable TAMPER IRQChannel */
+ NVIC_InitStructure.NVIC_IRQChannel = TAMPER_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/*******************************************************************************
+* Function Name : WriteToBackupReg
+* Description : Writes data Backup DRx registers.
+* Input : FirstBackupData: data to be written to Backup data registers.
+* Output : None
+* Return : None
+*******************************************************************************/
+void WriteToBackupReg(u16 FirstBackupData)
+{
+ u32 index = 0;
+
+ for (index = 0; index < BKP_DR_NUMBER; index++)
+ {
+ BKP_WriteBackupRegister(BKPDataReg[index], FirstBackupData + (index * 0x5A));
+ }
+}
+
+/*******************************************************************************
+* Function Name : CheckBackupReg
+* Description : Checks if the Backup DRx registers values are correct or not.
+* Input : FirstBackupData: data to be compared with Backup data registers.
+* Output : None
+* Return : - 0: All Backup DRx registers values are correct
+* - Value different from 0: Number of the first Backup register
+* which value is not correct
+*******************************************************************************/
+u32 CheckBackupReg(u16 FirstBackupData)
+{
+ u32 index = 0;
+
+ for (index = 0; index < BKP_DR_NUMBER; index++)
+ {
+ if (BKP_ReadBackupRegister(BKPDataReg[index]) != (FirstBackupData + (index * 0x5A)))
+ {
+ return (index + 1);
+ }
+ }
+
+ return 0;
+}
+
+/*******************************************************************************
+* Function Name : IsBackupRegReset
+* Description : Checks if the Backup DRx registers are reset or not.
+* Input : None
+* Output : None
+* Return : - 0: All Backup DRx registers are reset
+* - Value different from 0: Number of the first Backup register
+* not reset
+*******************************************************************************/
+u32 IsBackupRegReset(void)
+{
+ u32 index = 0;
+
+ for (index = 0; index < BKP_DR_NUMBER; index++)
+ {
+ if (BKP_ReadBackupRegister(BKPDataReg[index]) != 0x0000)
+ {
+ return (index + 1);
+ }
+ }
+
+ return 0;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/BKP/Tamper/main.h b/src/stm32lib/examples/BKP/Tamper/main.h new file mode 100755 index 0000000..e86ab09 --- /dev/null +++ b/src/stm32lib/examples/BKP/Tamper/main.h @@ -0,0 +1,32 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Header for main.c module
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __MAIN_H
+#define __MAIN_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+u32 IsBackupRegReset(void);
+
+#endif /* __MAIN_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/BKP/Tamper/platform_config.h b/src/stm32lib/examples/BKP/Tamper/platform_config.h new file mode 100755 index 0000000..e72d74d --- /dev/null +++ b/src/stm32lib/examples/BKP/Tamper/platform_config.h @@ -0,0 +1,46 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+ #define BKP_DR_NUMBER 10
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+ #define BKP_DR_NUMBER 42
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/BKP/Tamper/readme.txt b/src/stm32lib/examples/BKP/Tamper/readme.txt new file mode 100755 index 0000000..4e4eaa2 --- /dev/null +++ b/src/stm32lib/examples/BKP/Tamper/readme.txt @@ -0,0 +1,75 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the BKP Tamper Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to write/read data to/from Backup data registers and
+demonstrates the Tamper detection feature.
+
+The associated firmware performs the following:
+1. It configures the ANTI_TAMP pin to be active low, and enables the Tamper interrupt.
+2. It writes the data to all Backup data registers, then check whether the data were
+correctly written. If yes, the LED connected to GPIO_LED Pin 6 turns on, otherwise
+the LED connected to GPIO_LED Pin7 turns on.
+3. On applying a low level on the ANTI_TAMP pin (PC.13), the Backup data registers
+are reset and the Tamper interrupt is generated. The corresponding ISR then checks
+whether the Backup data registers are cleared. If yes, the LED connected to
+GPIO_LED Pin8 turns on, otherwise the LED connected to GPIO_LED Pin9 turns on.
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PC.06, PC.07, PC.08
+ and PC.09 pins
+ - Use the Tamper push-button connected to pin PC.13
+
+ + STM3210E-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PF.06, PF0.7, PF.08
+ and PF.09 pins
+ - Use the Tamper push-button connected to pin PC.13
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_pwr.c
+ + stm32f10x_bkp.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/BKP/Tamper/stm32f10x_conf.h b/src/stm32lib/examples/BKP/Tamper/stm32f10x_conf.h new file mode 100755 index 0000000..89fed06 --- /dev/null +++ b/src/stm32lib/examples/BKP/Tamper/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/BKP/Tamper/stm32f10x_it.c b/src/stm32lib/examples/BKP/Tamper/stm32f10x_it.c new file mode 100755 index 0000000..93a8588 --- /dev/null +++ b/src/stm32lib/examples/BKP/Tamper/stm32f10x_it.c @@ -0,0 +1,832 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "main.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+ if(BKP_GetITStatus() != RESET)
+ { /* Tamper detection event occured */
+
+ /* Check if Backup registers are cleared */
+ if(IsBackupRegReset() == 0)
+ {/* OK, Backup registers are reset as expected */
+ /* Turn on led connected to GPIO_LED Pin8 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_8, Bit_SET);
+ }
+ else
+ {/* Backup registers are not reset */
+ /* Turn on led connected to GPIO_LED Pin9 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_9, Bit_SET);
+ }
+
+ /* Clear Tamper pin interrupt pending bit */
+ BKP_ClearITPendingBit();
+
+ /* Clear Tamper pin Event(TE) pending flag */
+ BKP_ClearFlag();
+ }
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/BKP/Tamper/stm32f10x_it.h b/src/stm32lib/examples/BKP/Tamper/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/BKP/Tamper/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CAN/main.c b/src/stm32lib/examples/CAN/main.c new file mode 100755 index 0000000..3f20dda --- /dev/null +++ b/src/stm32lib/examples/CAN/main.c @@ -0,0 +1,383 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Local includes ------------------------------------------------------------*/
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+vu32 ret; /* for return of the interrupt handling */
+volatile TestStatus TestRx;
+ErrorStatus HSEStartUpStatus;
+
+/* Private functions ---------------------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus CAN_Polling(void);
+TestStatus CAN_Interrupt(void);
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* GPIO ports pins Configuration */
+ GPIO_Configuration();
+
+ /* CAN transmit at 100Kb/s and receive by polling in loopback mode */
+ TestRx = CAN_Polling();
+
+ if (TestRx == FAILED)
+ {
+ /* Turn on led connected to GPIO_LED pin8 (LD3) */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_8);
+ }
+ else
+ {
+ /* Turn on led connected to GPIO_LED pin6 (LD1) */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_6);
+ }
+
+ /* CAN transmit at 500Kb/s and receive by interrupt in loopback mode */
+ TestRx = CAN_Interrupt();
+
+ if (TestRx == FAILED)
+ {
+ /* Turn on led connected to GPIO_LED pin9 (LD4) */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_9);
+ }
+ else
+ {
+ /* Turn on led connected to GPIO_LED pin7 (LD2) */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_7);
+ }
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK */
+ RCC_PCLK1Config(RCC_HCLK_Div1);
+
+ /* Select HSE as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_HSE);
+
+ /* Wait till HSE is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x04)
+ {
+ }
+ }
+
+ /* GPIOA and GPIO_LED clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIO_LED, ENABLE);
+
+ /* CAN Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure GPIO_LED pin6, pin7, pin8 and pin9 as Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ /* Configure CAN pin: RX */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure CAN pin: TX */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures the NVIC and Vector Table base address.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Enable CAN RX0 interrupt IRQ channel */
+ NVIC_InitStructure.NVIC_IRQChannel = USB_LP_CAN_RX0_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : CAN_Polling
+* Description : Configures the CAN, transmit and receive by polling
+* Input : None
+* Output : None
+* Return : PASSED if the reception is well done, FAILED in other case
+*******************************************************************************/
+TestStatus CAN_Polling(void)
+{
+ CAN_InitTypeDef CAN_InitStructure;
+ CAN_FilterInitTypeDef CAN_FilterInitStructure;
+ CanTxMsg TxMessage;
+ CanRxMsg RxMessage;
+ u32 i = 0;
+ u8 TransmitMailbox;
+
+ /* CAN register init */
+ CAN_DeInit();
+ CAN_StructInit(&CAN_InitStructure);
+
+ /* CAN cell init */
+ CAN_InitStructure.CAN_TTCM=DISABLE;
+ CAN_InitStructure.CAN_ABOM=DISABLE;
+ CAN_InitStructure.CAN_AWUM=DISABLE;
+ CAN_InitStructure.CAN_NART=DISABLE;
+ CAN_InitStructure.CAN_RFLM=DISABLE;
+ CAN_InitStructure.CAN_TXFP=DISABLE;
+ CAN_InitStructure.CAN_Mode=CAN_Mode_LoopBack;
+ CAN_InitStructure.CAN_SJW=CAN_SJW_1tq;
+ CAN_InitStructure.CAN_BS1=CAN_BS1_8tq;
+ CAN_InitStructure.CAN_BS2=CAN_BS2_7tq;
+ CAN_InitStructure.CAN_Prescaler=5;
+ CAN_Init(&CAN_InitStructure);
+
+ /* CAN filter init */
+ CAN_FilterInitStructure.CAN_FilterNumber=0;
+ CAN_FilterInitStructure.CAN_FilterMode=CAN_FilterMode_IdMask;
+ CAN_FilterInitStructure.CAN_FilterScale=CAN_FilterScale_32bit;
+ CAN_FilterInitStructure.CAN_FilterIdHigh=0x0000;
+ CAN_FilterInitStructure.CAN_FilterIdLow=0x0000;
+ CAN_FilterInitStructure.CAN_FilterMaskIdHigh=0x0000;
+ CAN_FilterInitStructure.CAN_FilterMaskIdLow=0x0000;
+ CAN_FilterInitStructure.CAN_FilterFIFOAssignment=0;
+ CAN_FilterInitStructure.CAN_FilterActivation=ENABLE;
+ CAN_FilterInit(&CAN_FilterInitStructure);
+
+ /* transmit */
+ TxMessage.StdId=0x11;
+ TxMessage.RTR=CAN_RTR_DATA;
+ TxMessage.IDE=CAN_ID_STD;
+ TxMessage.DLC=2;
+ TxMessage.Data[0]=0xCA;
+ TxMessage.Data[1]=0xFE;
+
+ TransmitMailbox=CAN_Transmit(&TxMessage);
+ i = 0;
+ while((CAN_TransmitStatus(TransmitMailbox) != CANTXOK) && (i != 0xFF))
+ {
+ i++;
+ }
+
+ i = 0;
+ while((CAN_MessagePending(CAN_FIFO0) < 1) && (i != 0xFF))
+ {
+ i++;
+ }
+
+ /* receive */
+ RxMessage.StdId=0x00;
+ RxMessage.IDE=CAN_ID_STD;
+ RxMessage.DLC=0;
+ RxMessage.Data[0]=0x00;
+ RxMessage.Data[1]=0x00;
+ CAN_Receive(CAN_FIFO0, &RxMessage);
+
+ if (RxMessage.StdId!=0x11) return FAILED;
+
+ if (RxMessage.IDE!=CAN_ID_STD) return FAILED;
+
+ if (RxMessage.DLC!=2) return FAILED;
+
+ if ((RxMessage.Data[0]<<8|RxMessage.Data[1])!=0xCAFE) return FAILED;
+
+ return PASSED; /* Test Passed */
+}
+
+/*******************************************************************************
+* Function Name : CAN_Interrupt
+* Description : Configures the CAN, transmit and receive using interrupt.
+* Input : None
+* Output : None
+* Return : PASSED if the reception is well done, FAILED in other case
+*******************************************************************************/
+TestStatus CAN_Interrupt(void)
+{
+ CAN_InitTypeDef CAN_InitStructure;
+ CAN_FilterInitTypeDef CAN_FilterInitStructure;
+ CanTxMsg TxMessage;
+ u32 i = 0;
+
+ /* CAN register init */
+ CAN_DeInit();
+ CAN_StructInit(&CAN_InitStructure);
+
+ /* CAN cell init */
+ CAN_InitStructure.CAN_TTCM=DISABLE;
+ CAN_InitStructure.CAN_ABOM=DISABLE;
+ CAN_InitStructure.CAN_AWUM=DISABLE;
+ CAN_InitStructure.CAN_NART=DISABLE;
+ CAN_InitStructure.CAN_RFLM=DISABLE;
+ CAN_InitStructure.CAN_TXFP=DISABLE;
+ CAN_InitStructure.CAN_Mode=CAN_Mode_LoopBack;
+ CAN_InitStructure.CAN_SJW=CAN_SJW_1tq;
+ CAN_InitStructure.CAN_BS1=CAN_BS1_8tq;
+ CAN_InitStructure.CAN_BS2=CAN_BS2_7tq;
+ CAN_InitStructure.CAN_Prescaler=1;
+ CAN_Init(&CAN_InitStructure);
+
+ /* CAN filter init */
+ CAN_FilterInitStructure.CAN_FilterNumber=1;
+ CAN_FilterInitStructure.CAN_FilterMode=CAN_FilterMode_IdMask;
+ CAN_FilterInitStructure.CAN_FilterScale=CAN_FilterScale_32bit;
+ CAN_FilterInitStructure.CAN_FilterIdHigh=0x0000;
+ CAN_FilterInitStructure.CAN_FilterIdLow=0x0000;
+ CAN_FilterInitStructure.CAN_FilterMaskIdHigh=0x0000;
+ CAN_FilterInitStructure.CAN_FilterMaskIdLow=0x0000;
+ CAN_FilterInitStructure.CAN_FilterFIFOAssignment=CAN_FIFO0;
+ CAN_FilterInitStructure.CAN_FilterActivation=ENABLE;
+ CAN_FilterInit(&CAN_FilterInitStructure);
+
+ /* CAN FIFO0 message pending interrupt enable */
+ CAN_ITConfig(CAN_IT_FMP0, ENABLE);
+
+ /* transmit 1 message */
+ TxMessage.StdId=0x00;
+ TxMessage.ExtId=0x1234;
+ TxMessage.IDE=CAN_ID_EXT;
+ TxMessage.RTR=CAN_RTR_DATA;
+ TxMessage.DLC=2;
+ TxMessage.Data[0]=0xDE;
+ TxMessage.Data[1]=0xCA;
+ CAN_Transmit(&TxMessage);
+
+ /* initialize the value that will be returned */
+ ret = 0xFF;
+
+ /* receive message with interrupt handling */
+ i=0;
+ while((ret == 0xFF) && (i < 0xFFF))
+ {
+ i++;
+ }
+
+ if (i == 0xFFF)
+ {
+ ret=0;
+ }
+
+ /* disable interrupt handling */
+ CAN_ITConfig(CAN_IT_FMP0, DISABLE);
+
+ return (TestStatus)ret;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CAN/platform_config.h b/src/stm32lib/examples/CAN/platform_config.h new file mode 100755 index 0000000..0bc5169 --- /dev/null +++ b/src/stm32lib/examples/CAN/platform_config.h @@ -0,0 +1,44 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CAN/readme.txt b/src/stm32lib/examples/CAN/readme.txt new file mode 100755 index 0000000..27a02a6 --- /dev/null +++ b/src/stm32lib/examples/CAN/readme.txt @@ -0,0 +1,69 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the CAN example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to set a communication with the bxCAN
+in loopback mode.
+
+The CAN cell first performs a transmission and a reception of a standard data
+frame by polling at 100 Kbits/s. The received frame is checked and some LEDs light
+up to indicate whether the communication was successful. Then, an extended data
+frame is transmitted at 500 Kbits/s. Reception is done in the interrupt handler
+when the message becomes pending in the FIFO. Finally, the LEDs indicate if both
+transmission and reception have been successful.
+
+
+Directory contents
+==================
+platform_config.h Hardware configuration header file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PC.06, PC.07, PC.08
+ and PC.09 pins
+
+ + STM3210E-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PF.06, PF0.7, PF.08
+ and PF.09 pins
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_can.c
+ + stm32f10x_rcc.c
+ + stm32f10x_gpio.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/CAN/stm32f10x_conf.h b/src/stm32lib/examples/CAN/stm32f10x_conf.h new file mode 100755 index 0000000..538b790 --- /dev/null +++ b/src/stm32lib/examples/CAN/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CAN/stm32f10x_it.c b/src/stm32lib/examples/CAN/stm32f10x_it.c new file mode 100755 index 0000000..2803564 --- /dev/null +++ b/src/stm32lib/examples/CAN/stm32f10x_it.c @@ -0,0 +1,833 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+extern vu32 ret;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+ CanRxMsg RxMessage;
+
+ RxMessage.StdId=0x00;
+ RxMessage.ExtId=0x00;
+ RxMessage.IDE=0;
+ RxMessage.DLC=0;
+ RxMessage.FMI=0;
+ RxMessage.Data[0]=0x00;
+ RxMessage.Data[1]=0x00;
+
+ CAN_Receive(CAN_FIFO0, &RxMessage);
+
+ if((RxMessage.ExtId==0x1234) && (RxMessage.IDE==CAN_ID_EXT)
+ && (RxMessage.DLC==2) && ((RxMessage.Data[1]|RxMessage.Data[0]<<8)==0xDECA))
+ {
+ ret = 1;
+ }
+ else
+ {
+ ret = 0;
+ }
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CAN/stm32f10x_it.h b/src/stm32lib/examples/CAN/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/CAN/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CRC/main.c b/src/stm32lib/examples/CRC/main.c new file mode 100755 index 0000000..36f6596 --- /dev/null +++ b/src/stm32lib/examples/CRC/main.c @@ -0,0 +1,197 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define BUFFER_SIZE 114
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+
+static uc32 DataBuffer[BUFFER_SIZE] =
+ {
+ 0x00001021, 0x20423063, 0x408450a5, 0x60c670e7, 0x9129a14a, 0xb16bc18c,
+ 0xd1ade1ce, 0xf1ef1231, 0x32732252, 0x52b54294, 0x72f762d6, 0x93398318,
+ 0xa35ad3bd, 0xc39cf3ff, 0xe3de2462, 0x34430420, 0x64e674c7, 0x44a45485,
+ 0xa56ab54b, 0x85289509, 0xf5cfc5ac, 0xd58d3653, 0x26721611, 0x063076d7,
+ 0x569546b4, 0xb75ba77a, 0x97198738, 0xf7dfe7fe, 0xc7bc48c4, 0x58e56886,
+ 0x78a70840, 0x18612802, 0xc9ccd9ed, 0xe98ef9af, 0x89489969, 0xa90ab92b,
+ 0x4ad47ab7, 0x6a961a71, 0x0a503a33, 0x2a12dbfd, 0xfbbfeb9e, 0x9b798b58,
+ 0xbb3bab1a, 0x6ca67c87, 0x5cc52c22, 0x3c030c60, 0x1c41edae, 0xfd8fcdec,
+ 0xad2abd0b, 0x8d689d49, 0x7e976eb6, 0x5ed54ef4, 0x2e321e51, 0x0e70ff9f,
+ 0xefbedfdd, 0xcffcbf1b, 0x9f598f78, 0x918881a9, 0xb1caa1eb, 0xd10cc12d,
+ 0xe16f1080, 0x00a130c2, 0x20e35004, 0x40257046, 0x83b99398, 0xa3fbb3da,
+ 0xc33dd31c, 0xe37ff35e, 0x129022f3, 0x32d24235, 0x52146277, 0x7256b5ea,
+ 0x95a88589, 0xf56ee54f, 0xd52cc50d, 0x34e224c3, 0x04817466, 0x64475424,
+ 0x4405a7db, 0xb7fa8799, 0xe75ff77e, 0xc71dd73c, 0x26d336f2, 0x069116b0,
+ 0x76764615, 0x5634d94c, 0xc96df90e, 0xe92f99c8, 0xb98aa9ab, 0x58444865,
+ 0x78066827, 0x18c008e1, 0x28a3cb7d, 0xdb5ceb3f, 0xfb1e8bf9, 0x9bd8abbb,
+ 0x4a755a54, 0x6a377a16, 0x0af11ad0, 0x2ab33a92, 0xed0fdd6c, 0xcd4dbdaa,
+ 0xad8b9de8, 0x8dc97c26, 0x5c644c45, 0x3ca22c83, 0x1ce00cc1, 0xef1fff3e,
+ 0xdf7caf9b, 0xbfba8fd9, 0x9ff86e17, 0x7e364e55, 0x2e933eb2, 0x0ed11ef0
+ };
+
+vu32 CRCValue = 0;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+void Delay(vu32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* Enable CRC clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE);
+
+ /* Compute the CRC of "DataBuffer" */
+ CRCValue = CRC_CalcBlockCRC((u32 *)DataBuffer, BUFFER_SIZE);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for(; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CRC/readme.txt b/src/stm32lib/examples/CRC/readme.txt new file mode 100755 index 0000000..154cdca --- /dev/null +++ b/src/stm32lib/examples/CRC/readme.txt @@ -0,0 +1,51 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the CRC Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to use CRC (cyclic redundancy check) calculation unit to
+get a CRC code of a given buffer of data word(32-bit), based on a fixed generator
+polynomial(0x4C11DB7).
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_nvic.c
+ + stm32f10x_rcc.c
+ + stm32f10x_lib.c
+ + stm32f10x_flash.c
+ + stm32f10x_crc.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/CRC/stm32f10x_conf.h b/src/stm32lib/examples/CRC/stm32f10x_conf.h new file mode 100755 index 0000000..cc9f903 --- /dev/null +++ b/src/stm32lib/examples/CRC/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+//#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+//#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz */
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CRC/stm32f10x_it.c b/src/stm32lib/examples/CRC/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/CRC/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CRC/stm32f10x_it.h b/src/stm32lib/examples/CRC/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/CRC/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CortexM3/BitBand/main.c b/src/stm32lib/examples/CortexM3/BitBand/main.c new file mode 100755 index 0000000..36188fc --- /dev/null +++ b/src/stm32lib/examples/CortexM3/BitBand/main.c @@ -0,0 +1,191 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define RAM_BASE 0x20000000
+#define RAM_BB_BASE 0x22000000
+
+/* Private macro -------------------------------------------------------------*/
+#define Var_ResetBit_BB(VarAddr, BitNumber) \
+ (*(vu32 *) (RAM_BB_BASE | ((VarAddr - RAM_BASE) << 5) | ((BitNumber) << 2)) = 0)
+
+#define Var_SetBit_BB(VarAddr, BitNumber) \
+ (*(vu32 *) (RAM_BB_BASE | ((VarAddr - RAM_BASE) << 5) | ((BitNumber) << 2)) = 1)
+
+#define Var_GetBit_BB(VarAddr, BitNumber) \
+ (*(vu32 *) (RAM_BB_BASE | ((VarAddr - RAM_BASE) << 5) | ((BitNumber) << 2)))
+
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+vu32 Var, VarAddr = 0, VarBitValue = 0;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ Var = 0x00005AA5;
+
+ /* Clock configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+/* A mapping formula shows how to reference each word in the alias region to a corresponding
+bit in the bit-band region. The mapping formula is:
+ bit_word_addr = bit_band_base + (byte_offset x 32) + (bit_number × 4)
+
+where:
+ - bit_word_addr: is the address of the word in the alias memory region that maps to the
+ targeted bit.
+ - bit_band_base is the starting address of the alias region
+ - byte_offset is the number of the byte in the bit-band region that contains the targeted bit
+ - bit_number is the bit position (0-7) of the targeted bit */
+
+/* Get the variable address --------------------------------------------------*/
+ VarAddr = (u32)&Var;
+
+/* Modify variable bit using bit-band access ---------------------------------*/
+ /* Modify Var variable bit 0 -----------------------------------------------*/
+ Var_ResetBit_BB(VarAddr, 0); /* Var = 0x00005AA4 */
+ Var_SetBit_BB(VarAddr, 0); /* Var = 0x00005AA5 */
+
+ /* Modify Var variable bit 11 -----------------------------------------------*/
+ Var_ResetBit_BB(VarAddr, 11); /* Var = 0x000052A5 */
+ /* Get Var variable bit 11 value */
+ VarBitValue = Var_GetBit_BB(VarAddr, 11); /* VarBitValue = 0x00000000 */
+
+ Var_SetBit_BB(VarAddr, 11); /* Var = 0x00005AA5 */
+ /* Get Var variable bit 11 value */
+ VarBitValue = Var_GetBit_BB(VarAddr, 11); /* VarBitValue = 0x00000001 */
+
+ /* Modify Var variable bit 31 -----------------------------------------------*/
+ Var_SetBit_BB(VarAddr, 31); /* Var = 0x80005AA5 */
+ /* Get Var variable bit 31 value */
+ VarBitValue = Var_GetBit_BB(VarAddr, 31); /* VarBitValue = 0x00000001 */
+
+ Var_ResetBit_BB(VarAddr, 31); /* Var = 0x00005AA5 */
+ /* Get Var variable bit 31 value */
+ VarBitValue = Var_GetBit_BB(VarAddr, 31); /* VarBitValue = 0x00000000 */
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 0 wait state */
+ FLASH_SetLatency(FLASH_Latency_0);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK */
+ RCC_PCLK1Config(RCC_HCLK_Div1);
+
+ /* Select HSE as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_HSE);
+
+ /* Wait till HSE is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x04)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures NVIC and Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CortexM3/BitBand/readme.txt b/src/stm32lib/examples/CortexM3/BitBand/readme.txt new file mode 100755 index 0000000..4555c2c --- /dev/null +++ b/src/stm32lib/examples/CortexM3/BitBand/readme.txt @@ -0,0 +1,48 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the CortexM3 BitBand Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to use CortexM3 Bit-Band access to perform atomic read-modify-write
+and read operations on a varaible in SRAM.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_nvic.c
+ + stm32f10x_rcc.c
+ + stm32f10x_lib.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/CortexM3/BitBand/stm32f10x_conf.h b/src/stm32lib/examples/CortexM3/BitBand/stm32f10x_conf.h new file mode 100755 index 0000000..21a82d6 --- /dev/null +++ b/src/stm32lib/examples/CortexM3/BitBand/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+//#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+//#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CortexM3/BitBand/stm32f10x_it.c b/src/stm32lib/examples/CortexM3/BitBand/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/CortexM3/BitBand/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CortexM3/BitBand/stm32f10x_it.h b/src/stm32lib/examples/CortexM3/BitBand/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/CortexM3/BitBand/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CortexM3/Mode_Privilege/main.c b/src/stm32lib/examples/CortexM3/Mode_Privilege/main.c new file mode 100755 index 0000000..6946220 --- /dev/null +++ b/src/stm32lib/examples/CortexM3/Mode_Privilege/main.c @@ -0,0 +1,217 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define SP_PROCESS_SIZE 0x200 /* Process stack size */
+#define SP_PROCESS 0x02 /* Process stack */
+#define SP_MAIN 0x00 /* Main stack */
+#define THREAD_MODE_PRIVILEGED 0x00 /* Thread mode has privileged access */
+#define THREAD_MODE_UNPRIVILEGED 0x01 /* Thread mode has unprivileged access */
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+vu8 PSPMemAlloc[SP_PROCESS_SIZE];
+vu32 Index = 0, PSPValue = 0, CurrentStack = 0, ThreadMode = 0;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* Clock configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+
+/* Switch Thread mode Stack from Main to Process -----------------------------*/
+ /* Initialize memory reserved for Process Stack */
+ for(Index = 0; Index < SP_PROCESS_SIZE; Index++)
+ {
+ PSPMemAlloc[Index] = 0x00;
+ }
+
+ /* Set Process stack value */
+ __MSR_PSP((u32)PSPMemAlloc + SP_PROCESS_SIZE);
+
+ /* Select Process Stack as Thread mode Stack */
+ __MSR_CONTROL(SP_PROCESS);
+
+ /* Get the Thread mode stack used */
+ if((__MRS_CONTROL() & 0x02) == SP_MAIN)
+ {
+ /* Main stack is used as the current stack */
+ CurrentStack = SP_MAIN;
+ }
+ else
+ {
+ /* Process stack is used as the current stack */
+ CurrentStack = SP_PROCESS;
+
+ /* Get process stack pointer value */
+ PSPValue = __MRS_PSP();
+ }
+
+/* Switch Thread mode from privileged to unprivileged ------------------------*/
+ /* Thread mode has unprivileged access */
+ __MSR_CONTROL(THREAD_MODE_UNPRIVILEGED | SP_PROCESS);
+ /* Unprivileged access mainly affect ability to:
+ - Use or not use certain instructions such as MSR fields
+ - Access System Control Space (SCS) registers such as NVIC and SysTick */
+
+ /* Check Thread mode privilege status */
+ if((__MRS_CONTROL() & 0x01) == THREAD_MODE_PRIVILEGED)
+ {
+ /* Thread mode has privileged access */
+ ThreadMode = THREAD_MODE_PRIVILEGED;
+ }
+ else
+ {
+ /* Thread mode has unprivileged access*/
+ ThreadMode = THREAD_MODE_UNPRIVILEGED;
+ }
+
+/* Switch back Thread mode from unprivileged to privileged -------------------*/
+ /* Try to switch back Thread mode to privileged (Not possible, this can be
+ done only in Handler mode) */
+ __MSR_CONTROL(THREAD_MODE_PRIVILEGED | SP_PROCESS);
+
+ /* Generate a system call exception, and in the ISR switch back Thread mode
+ to privileged */
+ __SVC();
+
+ /* Check Thread mode privilege status */
+ if((__MRS_CONTROL() & 0x01) == THREAD_MODE_PRIVILEGED)
+ {
+ /* Thread mode has privileged access */
+ ThreadMode = THREAD_MODE_PRIVILEGED;
+ }
+ else
+ {
+ /* Thread mode has unprivileged access*/
+ ThreadMode = THREAD_MODE_UNPRIVILEGED;
+ }
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 0 wait state */
+ FLASH_SetLatency(FLASH_Latency_0);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK */
+ RCC_PCLK1Config(RCC_HCLK_Div1);
+
+ /* Select HSE as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_HSE);
+
+ /* Wait till HSE is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x04)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures NVIC and Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CortexM3/Mode_Privilege/readme.txt b/src/stm32lib/examples/CortexM3/Mode_Privilege/readme.txt new file mode 100755 index 0000000..12bd684 --- /dev/null +++ b/src/stm32lib/examples/CortexM3/Mode_Privilege/readme.txt @@ -0,0 +1,59 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the CortexM3 Mode_Privilege Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to modify CortexM3 Thread mode privilege access and stack.
+CortexM3 Thread mode is entered on Reset, and can be entered as a result of an
+exception return.
+
+The associated program is used to:
+1. Switch the Thread mode stack from Main stack to Process stack
+2. Switch the Thread mode from Privileged to Unprivileged
+3. Switch the Thread mode from Unprivileged back to Privileged
+
+To monitor the stack used and the privileged or unprivileged access level of code
+in Thread mode, a set of variables is available within the program. It is also
+possible to use the 'Cortex register' window of the debugger.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_nvic.c
+ + stm32f10x_rcc.c
+ + stm32f10x_lib.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/CortexM3/Mode_Privilege/stm32f10x_conf.h b/src/stm32lib/examples/CortexM3/Mode_Privilege/stm32f10x_conf.h new file mode 100755 index 0000000..21a82d6 --- /dev/null +++ b/src/stm32lib/examples/CortexM3/Mode_Privilege/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+//#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+//#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CortexM3/Mode_Privilege/stm32f10x_it.c b/src/stm32lib/examples/CortexM3/Mode_Privilege/stm32f10x_it.c new file mode 100755 index 0000000..d750dbc --- /dev/null +++ b/src/stm32lib/examples/CortexM3/Mode_Privilege/stm32f10x_it.c @@ -0,0 +1,812 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+ /* Switch back Thread mode to privileged */
+ __MSR_CONTROL(2);
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/CortexM3/Mode_Privilege/stm32f10x_it.h b/src/stm32lib/examples/CortexM3/Mode_Privilege/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/CortexM3/Mode_Privilege/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/flash b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/flash Binary files differnew file mode 100755 index 0000000..b9de87a --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/flash diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/flash.cfg b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/flash.cfg new file mode 100755 index 0000000..fd6a90b --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/flash.cfg @@ -0,0 +1,69 @@ +# Open On-Chip Debugger
+# (c) 2005 by Dominic Rath
+# (snapshot r247 from SVN tree + giveio, no official release, compiled my mifi)
+#
+# --help | -h display this help
+# --file | -f use configuration file <name>
+# --debug | -d set debug level <0-3>
+# --log_output | -l redirect log output to file <name>
+
+
+# daemon configuration
+
+# logging
+#debug 3
+
+# default ports
+telnet_port 4444
+gdb_port 3333
+
+daemon_startup reset
+
+#gdb_flash_program enable
+
+
+# interface configuration
+
+interface ft2232
+ft2232_device_desc "Olimex OpenOCD JTAG A"
+#ft2232_device_desc "Olimex OpenOCD JTAG TINY A"
+ft2232_layout olimex-jtag
+jtag_speed 10
+
+jtag_nsrst_delay 100
+jtag_ntrst_delay 100
+
+reset_config trst_and_srst
+
+
+# scan chain configuration
+
+# jtag_device L IRC IRCM IDCODE (Length, IR Capture, IR Capture Mask, IDCODE)
+jtag_device 4 0x1 0xf 0xe
+jtag_device 5 0x1 0x1 0x1e
+
+
+# target configuration
+
+# target <type> <startup mode>
+# target cortex_m3 <endianness> <reset mode> <chainpos> <variant>
+#target cortex_m3 little reset_halt 0
+#target cortex_m3 little run_and_halt 0
+#target cortex_m3 little reset_init 0 (this causes scripted flash write_image to fail)
+target cortex_m3 little run_and_init 0
+
+# run_and_halt_time <target> <time_in_ms>
+run_and_halt_time 0 0
+
+# working_area <target> <address> <size> <backup|nobackup>
+working_area 0 0x20000000 0x5000 nobackup
+
+# flash bank <driver> <base> <size> <chip_width> <bus_width> <target> [options]
+# flash bank stm32x <base> <size> 0 0 <target>
+flash bank stm32x 0x08000000 0x20000 0 0 0
+
+
+# script configuration
+
+# target_script <target> <event> <script_file>
+target_script 0 reset flash.script
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/flash.script b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/flash.script new file mode 100755 index 0000000..54eb165 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/flash.script @@ -0,0 +1,11 @@ +wait_halt
+sleep 10
+#poll
+#sleep 10
+stm32x mass_erase 0
+sleep 10
+flash write_image flash
+sleep 10
+reset run
+sleep 10
+shutdown
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/openocd.cfg b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/openocd.cfg new file mode 100755 index 0000000..34d57ff --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/openocd.cfg @@ -0,0 +1,60 @@ +# Open On-Chip Debugger
+# (c) 2005 by Dominic Rath
+# (snapshot r247 from SVN tree + giveio, no official release, compiled my mifi)
+#
+# --help | -h display this help
+# --file | -f use configuration file <name>
+# --debug | -d set debug level <0-3>
+# --log_output | -l redirect log output to file <name>
+
+
+# daemon configuration
+
+# logging
+#debug 3
+
+# default ports
+telnet_port 4444
+gdb_port 3333
+
+daemon_startup reset
+
+#gdb_flash_program enable
+
+
+# interface configuration
+
+interface ft2232
+ft2232_device_desc "Olimex OpenOCD JTAG"
+ft2232_layout olimex-jtag
+ft2232_vid_pid 0x15ba 0x0003
+
+jtag_nsrst_delay 100
+jtag_ntrst_delay 100
+
+reset_config trst_and_srst
+
+
+# scan chain configuration
+
+# jtag_device L IRC IRCM IDCODE (Length, IR Capture, IR Capture Mask, IDCODE)
+jtag_device 4 0x1 0xf 0xe
+jtag_device 5 0x1 0x1 0x1e
+
+
+# target configuration
+
+# target <type> <startup mode>
+# target cortex_m3 <endianness> <reset mode> <chainpos> <variant>
+target cortex_m3 little reset_halt 0
+#target cortex_m3 little run_and_halt 0
+
+# run_and_halt_time <target> <time_in_ms>
+#run_and_halt_time 0 0
+
+# working_area <target> <address> <size> <backup|nobackup>
+working_area 0 0x20000000 0x5000 nobackup
+
+# flash bank <driver> <base> <size> <chip_width> <bus_width> <target> [options]
+# flash bank stm32x <base> <size> 0 0 <target>
+flash bank stm32x 0x08000000 0x20000 0 0 0
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/target.ini b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/target.ini new file mode 100755 index 0000000..da18158 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/jtag/target.ini @@ -0,0 +1,93 @@ +#
+# GDB init file for STM32x family
+#
+
+set complaints 1
+set output-radix 16
+set input-radix 16
+
+# GDB must be set to big endian mode first if needed.
+#set endian little
+
+# add str9lib src to gdb search path
+#dir /cygdrive/c/progra~1/anglia/idealist/examples/stm32/libstr32x/src
+#dir C:/Progra~1/Anglia/IDEaliST/examples/stm32/libstm32x/src
+
+# change gdb prompt
+set prompt (arm-gdb)
+
+# You will need to change this to reflect the address of your jtag interface.
+#target remote localhost:2000
+
+# The libremote daemon must be set to big endian before the
+# executable is loaded.
+#monitor endian little
+
+# Increase the packet size to improve download speed.
+# to view current setting use:
+# show remote memory-write-packet-size
+
+set remote memory-write-packet-size 1024
+set remote memory-write-packet-size fixed
+
+set remote memory-read-packet-size 1024
+set remote memory-read-packet-size fixed
+set remote hardware-watchpoint-limit 6
+set remote hardware-breakpoint-limit 6
+
+# Load the program executable (ram only)
+#load
+
+# Set a breakpoint at main().
+#b main
+
+# Run to the breakpoint.
+#c
+
+#
+# GDB command helpers
+#
+
+#
+# reset and map 0 to internal ram
+#
+
+define ramreset
+reset
+set *(int*)0xE000ED08 = 0x20000000
+echo Internal RAM set to address 0x0.
+end
+
+#
+# reset and map 0 to flash
+#
+
+define flashreset
+reset
+thb main
+echo Internal Flash set to address 0x0.
+end
+
+#
+# reset target
+#
+
+define reset
+monitor reset
+end
+
+document ramreset
+ramreset
+Causes a target reset, remaps Internal RAM to address 0x0.
+end
+
+document flashreset
+flashreset
+Causes a target reset, remaps Internal Flash to address 0x0.
+A temporary breakpoint is set at start of function main
+end
+
+document reset
+reset
+Causes a target reset.
+end
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_128K_20K_FLASH.ld b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_128K_20K_FLASH.ld new file mode 100755 index 0000000..5e4ce87 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_128K_20K_FLASH.ld @@ -0,0 +1,29 @@ +/*
+Linker script for STM32F10x
+Copyright RAISONANCE 2007 (modified by Lanchon 1-Feb-2008)
+You can use, copy and distribute this file freely, but without any waranty.
+Configure memory sizes, end of stack and boot mode for your project here.
+*/
+
+
+/* include the common STM32F10x sub-script */
+INCLUDE "STM32_COMMON.ld"
+
+/* Memory Spaces Definitions */
+MEMORY
+{
+ RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K /* also change _estack below */
+ FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 128K
+ FLASHB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+ EXTMEMB0 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+ EXTMEMB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+ EXTMEMB2 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+ EXTMEMB3 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+}
+
+/* highest address of the user mode stack */
+_estack = 0x20005000;
+
+/* include the section management sub-script */
+/* (either "STM32_SEC_FLASH.ld" or "STM32_SEC_RAM.ld") */
+INCLUDE "STM32_SEC_FLASH.ld"
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_COMMON.ld b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_COMMON.ld new file mode 100755 index 0000000..6794c70 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_COMMON.ld @@ -0,0 +1,164 @@ +/*
+Common part of the linker scripts for STR32 devices
+Copyright RAISONANCE 2007
+You can use, modify and distribute thisfile freely, but without any waranty.
+*/
+
+
+/* default stack sizes.
+
+These are used by the startup in order to allocate stacks for the different modes.
+*/
+
+__Stack_Size = 1024 ;
+
+PROVIDE ( _Stack_Size = __Stack_Size ) ;
+
+__Stack_Init = _estack - __Stack_Size ;
+
+/*"PROVIDE" allows to easily override these values from an object file or the commmand line.*/
+PROVIDE ( _Stack_Init = __Stack_Init ) ;
+
+/*
+There will be a link error if there is not this amount of RAM free at the end.
+*/
+_Minimum_Stack_Size = 0x100 ;
+
+
+
+/*
+this sends all unreferenced IRQHandlers to reset
+*/
+
+
+PROVIDE ( Undefined_Handler = 0 ) ;
+PROVIDE ( SWI_Handler = 0 ) ;
+PROVIDE ( IRQ_Handler = 0 ) ;
+PROVIDE ( Prefetch_Handler = 0 ) ;
+PROVIDE ( Abort_Handler = 0 ) ;
+PROVIDE ( FIQ_Handler = 0 ) ;
+
+PROVIDE ( NMIException = 0 ) ;
+PROVIDE ( HardFaultException = 0 ) ;
+PROVIDE ( MemManageException = 0 ) ;
+PROVIDE ( BusFaultException = 0 ) ;
+PROVIDE ( UsageFaultException = 0 ) ;
+PROVIDE ( SVCHandler = 0 ) ;
+PROVIDE ( DebugMonitor = 0 ) ;
+PROVIDE ( PendSVC = 0 ) ;
+PROVIDE ( SysTickHandler = 0 ) ;
+PROVIDE ( WWDG_IRQHandler = 0 ) ;
+PROVIDE ( PVD_IRQHandler = 0 ) ;
+PROVIDE ( TAMPER_IRQHandler = 0 ) ;
+PROVIDE ( RTC_IRQHandler = 0 ) ;
+PROVIDE ( FLASH_IRQHandler = 0 ) ;
+PROVIDE ( RCC_IRQHandler = 0 ) ;
+PROVIDE ( EXTI0_IRQHandler = 0 ) ;
+PROVIDE ( EXTI1_IRQHandler = 0 ) ;
+PROVIDE ( EXTI2_IRQHandler = 0 ) ;
+PROVIDE ( EXTI3_IRQHandler = 0 ) ;
+PROVIDE ( EXTI4_IRQHandler = 0 ) ;
+PROVIDE ( DMAChannel1_IRQHandler = 0 ) ;
+PROVIDE ( DMAChannel2_IRQHandler = 0 ) ;
+PROVIDE ( DMAChannel3_IRQHandler = 0 ) ;
+PROVIDE ( DMAChannel4_IRQHandler = 0 ) ;
+PROVIDE ( DMAChannel5_IRQHandler = 0 ) ;
+PROVIDE ( DMAChannel6_IRQHandler = 0 ) ;
+PROVIDE ( DMAChannel7_IRQHandler = 0 ) ;
+PROVIDE ( ADC_IRQHandler = 0 ) ;
+PROVIDE ( USB_HP_CAN_TX_IRQHandler = 0 ) ;
+PROVIDE ( USB_LP_CAN_RX0_IRQHandler = 0 ) ;
+PROVIDE ( CAN_RX1_IRQHandler = 0 ) ;
+PROVIDE ( CAN_SCE_IRQHandler = 0 ) ;
+PROVIDE ( EXTI9_5_IRQHandler = 0 ) ;
+PROVIDE ( TIM1_BRK_IRQHandler = 0 ) ;
+PROVIDE ( TIM1_UP_IRQHandler = 0 ) ;
+PROVIDE ( TIM1_TRG_COM_IRQHandler = 0 ) ;
+PROVIDE ( TIM1_CC_IRQHandler = 0 ) ;
+PROVIDE ( TIM2_IRQHandler = 0 ) ;
+PROVIDE ( TIM3_IRQHandler = 0 ) ;
+PROVIDE ( TIM4_IRQHandler = 0 ) ;
+PROVIDE ( I2C1_EV_IRQHandler = 0 ) ;
+PROVIDE ( I2C1_ER_IRQHandler = 0 ) ;
+PROVIDE ( I2C2_EV_IRQHandler = 0 ) ;
+PROVIDE ( I2C2_ER_IRQHandler = 0 ) ;
+PROVIDE ( SPI1_IRQHandler = 0 ) ;
+PROVIDE ( SPI2_IRQHandler = 0 ) ;
+PROVIDE ( USART1_IRQHandler = 0 ) ;
+PROVIDE ( USART2_IRQHandler = 0 ) ;
+PROVIDE ( USART3_IRQHandler = 0 ) ;
+PROVIDE ( EXTI15_10_IRQHandler = 0 ) ;
+PROVIDE ( RTCAlarm_IRQHandler = 0 ) ;
+PROVIDE ( USBWakeUp_IRQHandler = 0 ) ;
+
+
+
+/******************************************************************************/
+/* Peripheral memory map */
+/******************************************************************************/
+/*this allows to compile the ST lib in "non-debug" mode*/
+
+
+/* Peripheral and SRAM base address in the alias region */
+PERIPH_BB_BASE = 0x42000000;
+SRAM_BB_BASE = 0x22000000;
+
+/* Peripheral and SRAM base address in the bit-band region */
+SRAM_BASE = 0x20000000;
+PERIPH_BASE = 0x40000000;
+
+/* Flash registers base address */
+PROVIDE ( FLASH_BASE = 0x40022000);
+/* Flash Option Bytes base address */
+PROVIDE ( OB_BASE = 0x1FFFF800);
+
+/* Peripheral memory map */
+APB1PERIPH_BASE = PERIPH_BASE ;
+APB2PERIPH_BASE = (PERIPH_BASE + 0x10000) ;
+AHBPERIPH_BASE = (PERIPH_BASE + 0x20000) ;
+
+PROVIDE ( TIM2 = (APB1PERIPH_BASE + 0x0000) ) ;
+PROVIDE ( TIM3 = (APB1PERIPH_BASE + 0x0400) ) ;
+PROVIDE ( TIM4 = (APB1PERIPH_BASE + 0x0800) ) ;
+PROVIDE ( RTC = (APB1PERIPH_BASE + 0x2800) ) ;
+PROVIDE ( WWDG = (APB1PERIPH_BASE + 0x2C00) ) ;
+PROVIDE ( IWDG = (APB1PERIPH_BASE + 0x3000) ) ;
+PROVIDE ( SPI2 = (APB1PERIPH_BASE + 0x3800) ) ;
+PROVIDE ( USART2 = (APB1PERIPH_BASE + 0x4400) ) ;
+PROVIDE ( USART3 = (APB1PERIPH_BASE + 0x4800) ) ;
+PROVIDE ( I2C1 = (APB1PERIPH_BASE + 0x5400) ) ;
+PROVIDE ( I2C2 = (APB1PERIPH_BASE + 0x5800) ) ;
+PROVIDE ( CAN = (APB1PERIPH_BASE + 0x6400) ) ;
+PROVIDE ( BKP = (APB1PERIPH_BASE + 0x6C00) ) ;
+PROVIDE ( PWR = (APB1PERIPH_BASE + 0x7000) ) ;
+
+PROVIDE ( AFIO = (APB2PERIPH_BASE + 0x0000) ) ;
+PROVIDE ( EXTI = (APB2PERIPH_BASE + 0x0400) ) ;
+PROVIDE ( GPIOA = (APB2PERIPH_BASE + 0x0800) ) ;
+PROVIDE ( GPIOB = (APB2PERIPH_BASE + 0x0C00) ) ;
+PROVIDE ( GPIOC = (APB2PERIPH_BASE + 0x1000) ) ;
+PROVIDE ( GPIOD = (APB2PERIPH_BASE + 0x1400) ) ;
+PROVIDE ( GPIOE = (APB2PERIPH_BASE + 0x1800) ) ;
+PROVIDE ( ADC1 = (APB2PERIPH_BASE + 0x2400) ) ;
+PROVIDE ( ADC2 = (APB2PERIPH_BASE + 0x2800) ) ;
+PROVIDE ( TIM1 = (APB2PERIPH_BASE + 0x2C00) ) ;
+PROVIDE ( SPI1 = (APB2PERIPH_BASE + 0x3000) ) ;
+PROVIDE ( USART1 = (APB2PERIPH_BASE + 0x3800) ) ;
+
+PROVIDE ( DMA = (AHBPERIPH_BASE + 0x0000) ) ;
+PROVIDE ( DMA_Channel1 = (AHBPERIPH_BASE + 0x0008) ) ;
+PROVIDE ( DMA_Channel2 = (AHBPERIPH_BASE + 0x001C) ) ;
+PROVIDE ( DMA_Channel3 = (AHBPERIPH_BASE + 0x0030) ) ;
+PROVIDE ( DMA_Channel4 = (AHBPERIPH_BASE + 0x0044) ) ;
+PROVIDE ( DMA_Channel5 = (AHBPERIPH_BASE + 0x0058) ) ;
+PROVIDE ( DMA_Channel6 = (AHBPERIPH_BASE + 0x006C) ) ;
+PROVIDE ( DMA_Channel7 = (AHBPERIPH_BASE + 0x0080) ) ;
+PROVIDE ( RCC = (AHBPERIPH_BASE + 0x1000) ) ;
+
+/* System Control Space memory map */
+SCS_BASE = 0xE000E000;
+
+PROVIDE ( SysTick = (SCS_BASE + 0x0010) ) ;
+PROVIDE ( NVIC = (SCS_BASE + 0x0100) ) ;
+PROVIDE ( SCB = (SCS_BASE + 0x0D00) ) ;
+
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_SEC_EXT.ld b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_SEC_EXT.ld new file mode 100755 index 0000000..3623d06 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_SEC_EXT.ld @@ -0,0 +1,181 @@ +/*
+Common part of the linker scripts for STR71x devices in EXT mode
+(that is, the EXT is seen at 0)
+Copyright RAISONANCE 2005
+You can use, modify and distribute thisfile freely, but without any waranty.
+*/
+
+
+
+/* Sections Definitions */
+
+SECTIONS
+{
+ /* the program code is stored in the .text section */
+ .text :
+ {
+ . = ALIGN(4);
+
+ *crt0*.o (.text) /* Startup code */
+ *startup.o (.text) /* Startup code */
+ *(.text) /* remaining code */
+ *(.rodata) /* read-only data (constants) */
+ *(.rodata*)
+ *(.glue_7)
+ *(.glue_7t)
+
+ . = ALIGN(4);
+ _etext = .;
+ /* This is used by the startup in order to initialize the .data secion */
+ _sidata = _etext ;
+ } >EXTMEMB0
+
+
+
+ /* This is the initialized data section
+ The program executes knowing that the data is in the RAM
+ but the loader puts the initial values in the EXTMEM.
+ It is one task of the startup to copy the initial values from EXTMEMB0 to RAM. */
+ .data : AT ( _etext )
+ {
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .data secion */
+ _sdata = . ;
+
+ *(.data)
+
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .data secion */
+ _edata = . ;
+ } >RAM
+
+
+
+ /* This is the uninitialized data section */
+ .bss :
+ {
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .bss secion */
+ _sbss = .;
+
+ *(.bss)
+ *(COMMON)
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .bss secion */
+ _ebss = . ;
+
+ } >RAM
+
+ PROVIDE ( end = _ebss );
+ PROVIDE ( _end = _ebss );
+
+ /* This is the user stack section
+ This is just to check that there is enough RAM left for the User mode stack
+ It should generate an error if it's full.
+ */
+ ._usrstack :
+ {
+ . = ALIGN(4);
+ _susrstack = . ;
+
+ . = . + _Minimum_Stack_Size ;
+
+ _eusrstack = ALIGN(4) ;
+ . = .;
+ } >RAM
+
+
+ /* this is the FLASH Bank0 */
+ /* the C or assembly source must explicitly place the code or data there
+ using the "section" attribute */
+ .fb0text :
+ {
+ *(.fb0text) /* remaining code */
+ *(.fb0rodata) /* read-only data (constants) */
+ *(.fb0rodata*)
+ } >FLASH
+
+ /* this is the FLASH Bank1 */
+ /* the C or assembly source must explicitly place the code or data there
+ using the "section" attribute */
+ .fb1text :
+ {
+ *(.fb1text) /* remaining code */
+ *(.fb1rodata) /* read-only data (constants) */
+ *(.fb1rodata*)
+ } >FLASHB1
+
+ /* EXTMEM Bank1 */
+ .eb1text :
+ {
+ *(.b1text) /* remaining code */
+ *(.b1rodata) /* read-only data (constants) */
+ *(.b1rodata*)
+ } >EXTMEMB1
+
+ /* EXTMEM Bank2 */
+ .eb2text :
+ {
+ *(.b2text) /* remaining code */
+ *(.b2rodata) /* read-only data (constants) */
+ *(.b2rodata*)
+ } >EXTMEMB2
+
+ /* EXTMEM Bank0 */
+ .eb3text :
+ {
+ *(.b3text) /* remaining code */
+ *(.b3rodata) /* read-only data (constants) */
+ *(.b3rodata*)
+ } >EXTMEMB3
+
+ __exidx_start = .;
+ __exidx_end = .;
+
+ /* after that it's only debugging information. */
+
+ /* remove the debugging information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ /* DWARF debug sections.
+ Symbols in the DWARF debugging sections are relative to the beginning
+ of the section so we begin them at 0. */
+ /* DWARF 1 */
+ .debug 0 : { *(.debug) }
+ .line 0 : { *(.line) }
+ /* GNU DWARF 1 extensions */
+ .debug_srcinfo 0 : { *(.debug_srcinfo) }
+ .debug_sfnames 0 : { *(.debug_sfnames) }
+ /* DWARF 1.1 and DWARF 2 */
+ .debug_aranges 0 : { *(.debug_aranges) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ /* DWARF 2 */
+ .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_frame 0 : { *(.debug_frame) }
+ .debug_str 0 : { *(.debug_str) }
+ .debug_loc 0 : { *(.debug_loc) }
+ .debug_macinfo 0 : { *(.debug_macinfo) }
+ /* SGI/MIPS DWARF 2 extensions */
+ .debug_weaknames 0 : { *(.debug_weaknames) }
+ .debug_funcnames 0 : { *(.debug_funcnames) }
+ .debug_typenames 0 : { *(.debug_typenames) }
+ .debug_varnames 0 : { *(.debug_varnames) }
+}
+
+
+
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_SEC_FLASH.ld b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_SEC_FLASH.ld new file mode 100755 index 0000000..cd8c4fa --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_SEC_FLASH.ld @@ -0,0 +1,201 @@ +/*
+Common part of the linker scripts for STR71x devices in FLASH mode
+(that is, the FLASH is seen at 0)
+Copyright RAISONANCE 2005
+You can use, modify and distribute thisfile freely, but without any waranty.
+*/
+
+
+
+/* Sections Definitions */
+
+SECTIONS
+{
+ /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* for some STRx devices, the beginning of the startup code is stored in the .flashtext section, which goes to FLASH */
+ .flashtext :
+ {
+ . = ALIGN(4);
+ *(.flashtext) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+
+ /* the program code is stored in the .text section, which goes to Flash */
+ .text :
+ {
+ . = ALIGN(4);
+
+ *(.text) /* remaining code */
+ *(.text.*) /* remaining code */
+ *(.rodata) /* read-only data (constants) */
+ *(.rodata*)
+ *(.glue_7)
+ *(.glue_7t)
+
+ . = ALIGN(4);
+ _etext = .;
+ /* This is used by the startup in order to initialize the .data secion */
+ _sidata = _etext;
+ } >FLASH
+
+
+
+ /* This is the initialized data section
+ The program executes knowing that the data is in the RAM
+ but the loader puts the initial values in the FLASH (inidata).
+ It is one task of the startup to copy the initial values from FLASH to RAM. */
+ .data : AT ( _sidata )
+ {
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .data secion */
+ _sdata = . ;
+
+ *(.data)
+ *(.data.*)
+
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .data secion */
+ _edata = . ;
+ } >RAM
+
+
+
+ /* This is the uninitialized data section */
+ .bss :
+ {
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .bss secion */
+ _sbss = .;
+
+ *(.bss)
+ *(COMMON)
+
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .bss secion */
+ _ebss = . ;
+ } >RAM
+
+ PROVIDE ( end = _ebss );
+ PROVIDE ( _end = _ebss );
+
+ /* This is the user stack section
+ This is just to check that there is enough RAM left for the User mode stack
+ It should generate an error if it's full.
+ */
+ ._usrstack :
+ {
+ . = ALIGN(4);
+ _susrstack = . ;
+
+ . = . + _Minimum_Stack_Size ;
+
+ . = ALIGN(4);
+ _eusrstack = . ;
+ } >RAM
+
+
+
+ /* this is the FLASH Bank1 */
+ /* the C or assembly source must explicitly place the code or data there
+ using the "section" attribute */
+ .b1text :
+ {
+ *(.b1text) /* remaining code */
+ *(.b1rodata) /* read-only data (constants) */
+ *(.b1rodata*)
+ } >FLASHB1
+
+ /* this is the EXTMEM */
+ /* the C or assembly source must explicitly place the code or data there
+ using the "section" attribute */
+
+ /* EXTMEM Bank0 */
+ .eb0text :
+ {
+ *(.eb0text) /* remaining code */
+ *(.eb0rodata) /* read-only data (constants) */
+ *(.eb0rodata*)
+ } >EXTMEMB0
+
+ /* EXTMEM Bank1 */
+ .eb1text :
+ {
+ *(.eb1text) /* remaining code */
+ *(.eb1rodata) /* read-only data (constants) */
+ *(.eb1rodata*)
+ } >EXTMEMB1
+
+ /* EXTMEM Bank2 */
+ .eb2text :
+ {
+ *(.eb2text) /* remaining code */
+ *(.eb2rodata) /* read-only data (constants) */
+ *(.eb2rodata*)
+ } >EXTMEMB2
+
+ /* EXTMEM Bank0 */
+ .eb3text :
+ {
+ *(.eb3text) /* remaining code */
+ *(.eb3rodata) /* read-only data (constants) */
+ *(.eb3rodata*)
+ } >EXTMEMB3
+
+ __exidx_start = .;
+ __exidx_end = .;
+
+ /* after that it's only debugging information. */
+
+ /* remove the debugging information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ /* DWARF debug sections.
+ Symbols in the DWARF debugging sections are relative to the beginning
+ of the section so we begin them at 0. */
+ /* DWARF 1 */
+ .debug 0 : { *(.debug) }
+ .line 0 : { *(.line) }
+ /* GNU DWARF 1 extensions */
+ .debug_srcinfo 0 : { *(.debug_srcinfo) }
+ .debug_sfnames 0 : { *(.debug_sfnames) }
+ /* DWARF 1.1 and DWARF 2 */
+ .debug_aranges 0 : { *(.debug_aranges) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ /* DWARF 2 */
+ .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_frame 0 : { *(.debug_frame) }
+ .debug_str 0 : { *(.debug_str) }
+ .debug_loc 0 : { *(.debug_loc) }
+ .debug_macinfo 0 : { *(.debug_macinfo) }
+ /* SGI/MIPS DWARF 2 extensions */
+ .debug_weaknames 0 : { *(.debug_weaknames) }
+ .debug_funcnames 0 : { *(.debug_funcnames) }
+ .debug_typenames 0 : { *(.debug_typenames) }
+ .debug_varnames 0 : { *(.debug_varnames) }
+}
+
+
+
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_SEC_RAM.ld b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_SEC_RAM.ld new file mode 100755 index 0000000..4b44bb2 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_SEC_RAM.ld @@ -0,0 +1,156 @@ +/*
+Common part of the linker scripts for STR71x devices in RAM mode
+(that is, the RAM is seen at 0 and we assume that the loader initializes it)
+Copyright RAISONANCE 2005
+You can use, modify and distribute thisfile freely, but without any waranty.
+*/
+
+/* Sections Definitions */
+
+SECTIONS
+{
+
+ /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to start of RAM */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >RAM
+
+ /* for some STRx devices, the beginning of the startup code is stored in the .flashtext section, which goes to FLASH */
+ .flashtext :
+ {
+ . = ALIGN(4);
+ *(.flashtext) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* the program code is stored in the .text section, which goes to RAM */
+ .text :
+ {
+ . = ALIGN(4);
+
+ *(.text ) /* remaining code */
+ *(.glue_7)
+ *(.glue_7t)
+
+ . = ALIGN(4);
+ } >RAM
+
+ /* This is the uninitialized data section. */
+ .bss :
+ {
+ . = ALIGN(4);
+ _sbss = .;
+
+ *(.bss)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = . ;
+ _etext = _ebss ;
+
+ } >RAM
+
+
+ /* read-only data (constants) */
+ .rodata :
+ {
+ *(.rodata)
+ *(.rodata*)
+ . = ALIGN(4);
+ } > FLASH
+
+
+ .idata :
+ {
+ _sidata = . ;
+ } > FLASH
+
+
+ /* This is the initialized data section. */
+ .data : AT ( _sidata )
+ {
+ . = ALIGN(4);
+ _sdata = .;
+ *(.data)
+ . = ALIGN(4);
+ _edata = . ;
+ } >RAM
+
+
+
+ PROVIDE ( end = _edata );
+ PROVIDE ( _end = _edata );
+
+ /* This is the user stack section
+ This is just to check that there is enough RAM left for the User mode stack
+ It should generate an error if it's full.
+ */
+ ._usrstack :
+ {
+ . = ALIGN(4);
+ _susrstack = . ;
+
+ . = . + _Minimum_Stack_Size ;
+
+ . = ALIGN(4);
+ _eusrstack = . ;
+ } >RAM
+
+
+ __exidx_start = .;
+ __exidx_end = .;
+
+ /* after that it's only debugging information. */
+
+ /* remove the debugging information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ /* DWARF debug sections.
+ Symbols in the DWARF debugging sections are relative to the beginning
+ of the section so we begin them at 0. */
+ /* DWARF 1 */
+ .debug 0 : { *(.debug) }
+ .line 0 : { *(.line) }
+ /* GNU DWARF 1 extensions */
+ .debug_srcinfo 0 : { *(.debug_srcinfo) }
+ .debug_sfnames 0 : { *(.debug_sfnames) }
+ /* DWARF 1.1 and DWARF 2 */
+ .debug_aranges 0 : { *(.debug_aranges) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ /* DWARF 2 */
+/* .debug_info 0 : { * ( EXCLUDE_FILE ( *libc.a *libm.a ) .debug_info .gnu.linkonce.wi.*) }*/
+ .debug_info 0 : { * ( .debug_info .gnu.linkonce.wi.*) }
+/* .debug_abbrev 0 : { *(EXCLUDE_FILE ( *libc.a *libm.a ) .debug_abbrev) }*/
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+/* .debug_line 0 : { *(EXCLUDE_FILE ( *libc.a *libm.a ) .debug_line) }*/
+ .debug_line 0 : { *( .debug_line) }
+ /* (*(EXCLUDE_FILE (*crtend.o *otherfile.o) .ctors)) */
+ .debug_frame 0 : { *(.debug_frame) }
+ .debug_str 0 : { *(.debug_str) }
+ .debug_loc 0 : { *(.debug_loc) }
+ .debug_macinfo 0 : { *(.debug_macinfo) }
+ /* SGI/MIPS DWARF 2 extensions */
+ .debug_weaknames 0 : { *(.debug_weaknames) }
+ .debug_funcnames 0 : { *(.debug_funcnames) }
+ .debug_typenames 0 : { *(.debug_typenames) }
+ .debug_varnames 0 : { *(.debug_varnames) }
+}
+
+
+
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_SEC_RAMonly.ld b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_SEC_RAMonly.ld new file mode 100755 index 0000000..fa90799 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/STM32_SEC_RAMonly.ld @@ -0,0 +1,157 @@ +/*
+Common part of the linker scripts for STR71x devices in RAM mode
+(that is, the RAM is seen at 0 and we assume that the loader initializes it)
+Copyright RAISONANCE 2005
+You can use, modify and distribute thisfile freely, but without any waranty.
+*/
+
+/* Sections Definitions */
+
+SECTIONS
+{
+
+ /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to start of RAM */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ *(.isr_vector) /* Startup code */
+ . = ALIGN(4);
+ } >RAM
+
+
+ /* the beginning of the startup code is stored in the .flashtext section */
+ .flashtext :
+ {
+ . = ALIGN(4);
+
+ *crt0*.o (.flashtext) /* Startup code */
+ *startup.o (.flashtext) /* Startup code */
+ *(.flashtext) /* Startup code */
+ . = ALIGN(4);
+ } >RAM
+
+ /* the program code is stored in the .text section */
+ .text :
+ {
+ . = ALIGN(4);
+
+ *crt0*.o (.text) /* Startup code */
+ *startup.o (.text) /* Startup code */
+ *(.text ) /* remaining code */
+ *(.glue_7)
+ *(.glue_7t)
+
+ . = ALIGN(4);
+ } >RAM
+
+ /* This is the uninitialized data section. */
+ .bss :
+ {
+ . = ALIGN(4);
+ _sbss = .;
+
+ *(.bss)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = . ;
+ _etext = _ebss ;
+
+ } >RAM
+
+
+ /* read-only data (constants) */
+ .rodata :
+ {
+ *(.rodata)
+ *(.rodata*)
+ . = ALIGN(4);
+ } > RAM
+
+
+ /* This is the initialized data section. */
+ .data :
+ {
+ . = ALIGN(4);
+ _sidata = . ; /*this is useless but allows the same startup as for the other modes to be used.*/
+ _sdata = .;
+ *(.data)
+ . = ALIGN(4);
+ _edata = . ;
+ } >RAM
+
+
+
+ PROVIDE ( end = _edata );
+ PROVIDE ( _end = _edata );
+
+ /* This is the user stack section
+ This is just to check that there is enough RAM left for the User mode stack
+ It should generate an error if it's full.
+ */
+ ._usrstack :
+ {
+ . = ALIGN(4);
+ _susrstack = . ;
+
+ . = . + _Minimum_Stack_Size ;
+
+ . = ALIGN(4);
+ _eusrstack = . ;
+ } >RAM
+
+
+ __exidx_start = .;
+ __exidx_end = .;
+
+ /* after that it's only debugging information. */
+
+ /* remove the debugging information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ /* DWARF debug sections.
+ Symbols in the DWARF debugging sections are relative to the beginning
+ of the section so we begin them at 0. */
+ /* DWARF 1 */
+ .debug 0 : { *(.debug) }
+ .line 0 : { *(.line) }
+ /* GNU DWARF 1 extensions */
+ .debug_srcinfo 0 : { *(.debug_srcinfo) }
+ .debug_sfnames 0 : { *(.debug_sfnames) }
+ /* DWARF 1.1 and DWARF 2 */
+ .debug_aranges 0 : { *(.debug_aranges) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ /* DWARF 2 */
+/* .debug_info 0 : { * ( EXCLUDE_FILE ( *libc.a *libm.a ) .debug_info .gnu.linkonce.wi.*) }*/
+ .debug_info 0 : { * ( .debug_info .gnu.linkonce.wi.*) }
+/* .debug_abbrev 0 : { *(EXCLUDE_FILE ( *libc.a *libm.a ) .debug_abbrev) }*/
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+/* .debug_line 0 : { *(EXCLUDE_FILE ( *libc.a *libm.a ) .debug_line) }*/
+ .debug_line 0 : { *( .debug_line) }
+ /* (*(EXCLUDE_FILE (*crtend.o *otherfile.o) .ctors)) */
+ .debug_frame 0 : { *(.debug_frame) }
+ .debug_str 0 : { *(.debug_str) }
+ .debug_loc 0 : { *(.debug_loc) }
+ .debug_macinfo 0 : { *(.debug_macinfo) }
+ /* SGI/MIPS DWARF 2 extensions */
+ .debug_weaknames 0 : { *(.debug_weaknames) }
+ .debug_funcnames 0 : { *(.debug_funcnames) }
+ .debug_typenames 0 : { *(.debug_typenames) }
+ .debug_varnames 0 : { *(.debug_varnames) }
+}
+
+
+
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/cortexm3_macro.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/cortexm3_macro.h new file mode 100755 index 0000000..19e8f7a --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/cortexm3_macro.h @@ -0,0 +1,53 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : cortexm3_macro.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Header file for cortexm3_macro.s.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __CORTEXM3_MACRO_H
+#define __CORTEXM3_MACRO_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void __WFI(void);
+void __WFE(void);
+void __SEV(void);
+void __ISB(void);
+void __DSB(void);
+void __DMB(void);
+void __SVC(void);
+u32 __MRS_CONTROL(void);
+void __MSR_CONTROL(u32 Control);
+u32 __MRS_PSP(void);
+void __MSR_PSP(u32 TopOfProcessStack);
+u32 __MRS_MSP(void);
+void __MSR_MSP(u32 TopOfMainStack);
+void __RESETPRIMASK(void);
+void __SETPRIMASK(void);
+u32 __READ_PRIMASK(void);
+void __RESETFAULTMASK(void);
+void __SETFAULTMASK(void);
+u32 __READ_FAULTMASK(void);
+void __BASEPRICONFIG(u32 NewPriority);
+u32 __GetBASEPRI(void);
+u16 __REV_HalfWord(u16 Data);
+u32 __REV_Word(u32 Data);
+
+#endif /* __CORTEXM3_MACRO_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_adc.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_adc.h new file mode 100755 index 0000000..c14f4fd --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_adc.h @@ -0,0 +1,300 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_adc.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* ADC firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_ADC_H
+#define __STM32F10x_ADC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* ADC Init structure definition */
+typedef struct
+{
+ u32 ADC_Mode;
+ FunctionalState ADC_ScanConvMode;
+ FunctionalState ADC_ContinuousConvMode;
+ u32 ADC_ExternalTrigConv;
+ u32 ADC_DataAlign;
+ u8 ADC_NbrOfChannel;
+}ADC_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+#define IS_ADC_ALL_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == ADC1_BASE) || \
+ ((*(u32*)&(PERIPH)) == ADC2_BASE) || \
+ ((*(u32*)&(PERIPH)) == ADC3_BASE))
+
+#define IS_ADC_DMA_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == ADC1_BASE) || \
+ ((*(u32*)&(PERIPH)) == ADC3_BASE))
+
+/* ADC dual mode -------------------------------------------------------------*/
+#define ADC_Mode_Independent ((u32)0x00000000)
+#define ADC_Mode_RegInjecSimult ((u32)0x00010000)
+#define ADC_Mode_RegSimult_AlterTrig ((u32)0x00020000)
+#define ADC_Mode_InjecSimult_FastInterl ((u32)0x00030000)
+#define ADC_Mode_InjecSimult_SlowInterl ((u32)0x00040000)
+#define ADC_Mode_InjecSimult ((u32)0x00050000)
+#define ADC_Mode_RegSimult ((u32)0x00060000)
+#define ADC_Mode_FastInterl ((u32)0x00070000)
+#define ADC_Mode_SlowInterl ((u32)0x00080000)
+#define ADC_Mode_AlterTrig ((u32)0x00090000)
+
+#define IS_ADC_MODE(MODE) (((MODE) == ADC_Mode_Independent) || \
+ ((MODE) == ADC_Mode_RegInjecSimult) || \
+ ((MODE) == ADC_Mode_RegSimult_AlterTrig) || \
+ ((MODE) == ADC_Mode_InjecSimult_FastInterl) || \
+ ((MODE) == ADC_Mode_InjecSimult_SlowInterl) || \
+ ((MODE) == ADC_Mode_InjecSimult) || \
+ ((MODE) == ADC_Mode_RegSimult) || \
+ ((MODE) == ADC_Mode_FastInterl) || \
+ ((MODE) == ADC_Mode_SlowInterl) || \
+ ((MODE) == ADC_Mode_AlterTrig))
+
+/* ADC extrenal trigger sources for regular channels conversion --------------*/
+/* for ADC1 and ADC2 */
+#define ADC_ExternalTrigConv_T1_CC1 ((u32)0x00000000)
+#define ADC_ExternalTrigConv_T1_CC2 ((u32)0x00020000)
+#define ADC_ExternalTrigConv_T2_CC2 ((u32)0x00060000)
+#define ADC_ExternalTrigConv_T3_TRGO ((u32)0x00080000)
+#define ADC_ExternalTrigConv_T4_CC4 ((u32)0x000A0000)
+#define ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO ((u32)0x000C0000)
+/* for ADC1, ADC2 and ADC3 */
+#define ADC_ExternalTrigConv_T1_CC3 ((u32)0x00040000)
+#define ADC_ExternalTrigConv_None ((u32)0x000E0000)
+/* for ADC3 */
+#define ADC_ExternalTrigConv_T3_CC1 ((u32)0x00000000)
+#define ADC_ExternalTrigConv_T2_CC3 ((u32)0x00020000)
+#define ADC_ExternalTrigConv_T8_CC1 ((u32)0x00060000)
+#define ADC_ExternalTrigConv_T8_TRGO ((u32)0x00080000)
+#define ADC_ExternalTrigConv_T5_CC1 ((u32)0x000A0000)
+#define ADC_ExternalTrigConv_T5_CC3 ((u32)0x000C0000)
+
+#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_ExternalTrigConv_T1_CC1) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T1_CC2) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T1_CC3) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T2_CC2) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T3_TRGO) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T4_CC4) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_None) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T3_CC1) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T2_CC3) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T8_CC1) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T8_TRGO) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T5_CC1) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T5_CC3))
+
+/* ADC data align ------------------------------------------------------------*/
+#define ADC_DataAlign_Right ((u32)0x00000000)
+#define ADC_DataAlign_Left ((u32)0x00000800)
+
+#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DataAlign_Right) || \
+ ((ALIGN) == ADC_DataAlign_Left))
+
+/* ADC channels --------------------------------------------------------------*/
+#define ADC_Channel_0 ((u8)0x00)
+#define ADC_Channel_1 ((u8)0x01)
+#define ADC_Channel_2 ((u8)0x02)
+#define ADC_Channel_3 ((u8)0x03)
+#define ADC_Channel_4 ((u8)0x04)
+#define ADC_Channel_5 ((u8)0x05)
+#define ADC_Channel_6 ((u8)0x06)
+#define ADC_Channel_7 ((u8)0x07)
+#define ADC_Channel_8 ((u8)0x08)
+#define ADC_Channel_9 ((u8)0x09)
+#define ADC_Channel_10 ((u8)0x0A)
+#define ADC_Channel_11 ((u8)0x0B)
+#define ADC_Channel_12 ((u8)0x0C)
+#define ADC_Channel_13 ((u8)0x0D)
+#define ADC_Channel_14 ((u8)0x0E)
+#define ADC_Channel_15 ((u8)0x0F)
+#define ADC_Channel_16 ((u8)0x10)
+#define ADC_Channel_17 ((u8)0x11)
+
+#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) == ADC_Channel_0) || ((CHANNEL) == ADC_Channel_1) || \
+ ((CHANNEL) == ADC_Channel_2) || ((CHANNEL) == ADC_Channel_3) || \
+ ((CHANNEL) == ADC_Channel_4) || ((CHANNEL) == ADC_Channel_5) || \
+ ((CHANNEL) == ADC_Channel_6) || ((CHANNEL) == ADC_Channel_7) || \
+ ((CHANNEL) == ADC_Channel_8) || ((CHANNEL) == ADC_Channel_9) || \
+ ((CHANNEL) == ADC_Channel_10) || ((CHANNEL) == ADC_Channel_11) || \
+ ((CHANNEL) == ADC_Channel_12) || ((CHANNEL) == ADC_Channel_13) || \
+ ((CHANNEL) == ADC_Channel_14) || ((CHANNEL) == ADC_Channel_15) || \
+ ((CHANNEL) == ADC_Channel_16) || ((CHANNEL) == ADC_Channel_17))
+
+/* ADC sampling times --------------------------------------------------------*/
+#define ADC_SampleTime_1Cycles5 ((u8)0x00)
+#define ADC_SampleTime_7Cycles5 ((u8)0x01)
+#define ADC_SampleTime_13Cycles5 ((u8)0x02)
+#define ADC_SampleTime_28Cycles5 ((u8)0x03)
+#define ADC_SampleTime_41Cycles5 ((u8)0x04)
+#define ADC_SampleTime_55Cycles5 ((u8)0x05)
+#define ADC_SampleTime_71Cycles5 ((u8)0x06)
+#define ADC_SampleTime_239Cycles5 ((u8)0x07)
+
+#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SampleTime_1Cycles5) || \
+ ((TIME) == ADC_SampleTime_7Cycles5) || \
+ ((TIME) == ADC_SampleTime_13Cycles5) || \
+ ((TIME) == ADC_SampleTime_28Cycles5) || \
+ ((TIME) == ADC_SampleTime_41Cycles5) || \
+ ((TIME) == ADC_SampleTime_55Cycles5) || \
+ ((TIME) == ADC_SampleTime_71Cycles5) || \
+ ((TIME) == ADC_SampleTime_239Cycles5))
+
+/* ADC extrenal trigger sources for injected channels conversion -------------*/
+/* For ADC1 and ADC2 */
+#define ADC_ExternalTrigInjecConv_T2_TRGO ((u32)0x00002000)
+#define ADC_ExternalTrigInjecConv_T2_CC1 ((u32)0x00003000)
+#define ADC_ExternalTrigInjecConv_T3_CC4 ((u32)0x00004000)
+#define ADC_ExternalTrigInjecConv_T4_TRGO ((u32)0x00005000)
+#define ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4 ((u32)0x00006000)
+/* For ADC1, ADC2 and ADC3 */
+#define ADC_ExternalTrigInjecConv_T1_TRGO ((u32)0x00000000)
+#define ADC_ExternalTrigInjecConv_T1_CC4 ((u32)0x00001000)
+#define ADC_ExternalTrigInjecConv_None ((u32)0x00007000)
+/* For ADC3 */
+#define ADC_ExternalTrigInjecConv_T4_CC3 ((u32)0x00002000)
+#define ADC_ExternalTrigInjecConv_T8_CC2 ((u32)0x00003000)
+#define ADC_ExternalTrigInjecConv_T8_CC4 ((u32)0x00004000)
+#define ADC_ExternalTrigInjecConv_T5_TRGO ((u32)0x00005000)
+#define ADC_ExternalTrigInjecConv_T5_CC4 ((u32)0x00006000)
+
+#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_ExternalTrigInjecConv_T1_TRGO) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T1_CC4) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_TRGO) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_CC1) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T3_CC4) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_TRGO) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_None) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC3) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC2) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC4) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_TRGO) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_CC4))
+
+/* ADC injected channel selection --------------------------------------------*/
+#define ADC_InjectedChannel_1 ((u8)0x14)
+#define ADC_InjectedChannel_2 ((u8)0x18)
+#define ADC_InjectedChannel_3 ((u8)0x1C)
+#define ADC_InjectedChannel_4 ((u8)0x20)
+
+#define IS_ADC_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) == ADC_InjectedChannel_1) || \
+ ((CHANNEL) == ADC_InjectedChannel_2) || \
+ ((CHANNEL) == ADC_InjectedChannel_3) || \
+ ((CHANNEL) == ADC_InjectedChannel_4))
+
+/* ADC analog watchdog selection ---------------------------------------------*/
+#define ADC_AnalogWatchdog_SingleRegEnable ((u32)0x00800200)
+#define ADC_AnalogWatchdog_SingleInjecEnable ((u32)0x00400200)
+#define ADC_AnalogWatchdog_SingleRegOrInjecEnable ((u32)0x00C00200)
+#define ADC_AnalogWatchdog_AllRegEnable ((u32)0x00800000)
+#define ADC_AnalogWatchdog_AllInjecEnable ((u32)0x00400000)
+#define ADC_AnalogWatchdog_AllRegAllInjecEnable ((u32)0x00C00000)
+#define ADC_AnalogWatchdog_None ((u32)0x00000000)
+
+#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_AnalogWatchdog_SingleRegEnable) || \
+ ((WATCHDOG) == ADC_AnalogWatchdog_SingleInjecEnable) || \
+ ((WATCHDOG) == ADC_AnalogWatchdog_SingleRegOrInjecEnable) || \
+ ((WATCHDOG) == ADC_AnalogWatchdog_AllRegEnable) || \
+ ((WATCHDOG) == ADC_AnalogWatchdog_AllInjecEnable) || \
+ ((WATCHDOG) == ADC_AnalogWatchdog_AllRegAllInjecEnable) || \
+ ((WATCHDOG) == ADC_AnalogWatchdog_None))
+
+/* ADC interrupts definition -------------------------------------------------*/
+#define ADC_IT_EOC ((u16)0x0220)
+#define ADC_IT_AWD ((u16)0x0140)
+#define ADC_IT_JEOC ((u16)0x0480)
+
+#define IS_ADC_IT(IT) ((((IT) & (u16)0xF81F) == 0x00) && ((IT) != 0x00))
+#define IS_ADC_GET_IT(IT) (((IT) == ADC_IT_EOC) || ((IT) == ADC_IT_AWD) || \
+ ((IT) == ADC_IT_JEOC))
+
+/* ADC flags definition ------------------------------------------------------*/
+#define ADC_FLAG_AWD ((u8)0x01)
+#define ADC_FLAG_EOC ((u8)0x02)
+#define ADC_FLAG_JEOC ((u8)0x04)
+#define ADC_FLAG_JSTRT ((u8)0x08)
+#define ADC_FLAG_STRT ((u8)0x10)
+
+#define IS_ADC_CLEAR_FLAG(FLAG) ((((FLAG) & (u8)0xE0) == 0x00) && ((FLAG) != 0x00))
+#define IS_ADC_GET_FLAG(FLAG) (((FLAG) == ADC_FLAG_AWD) || ((FLAG) == ADC_FLAG_EOC) || \
+ ((FLAG) == ADC_FLAG_JEOC) || ((FLAG)== ADC_FLAG_JSTRT) || \
+ ((FLAG) == ADC_FLAG_STRT))
+
+/* ADC thresholds ------------------------------------------------------------*/
+#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFF)
+
+/* ADC injected offset -------------------------------------------------------*/
+#define IS_ADC_OFFSET(OFFSET) ((OFFSET) <= 0xFFF)
+
+/* ADC injected length -------------------------------------------------------*/
+#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x4))
+
+/* ADC injected rank ---------------------------------------------------------*/
+#define IS_ADC_INJECTED_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x4))
+
+/* ADC regular length --------------------------------------------------------*/
+#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x10))
+
+/* ADC regular rank ----------------------------------------------------------*/
+#define IS_ADC_REGULAR_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x10))
+
+/* ADC regular discontinuous mode number -------------------------------------*/
+#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 0x1) && ((NUMBER) <= 0x8))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void ADC_DeInit(ADC_TypeDef* ADCx);
+void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct);
+void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct);
+void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_ITConfig(ADC_TypeDef* ADCx, u16 ADC_IT, FunctionalState NewState);
+void ADC_ResetCalibration(ADC_TypeDef* ADCx);
+FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx);
+void ADC_StartCalibration(ADC_TypeDef* ADCx);
+FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx);
+void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx);
+void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, u8 Number);
+void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel, u8 Rank, u8 ADC_SampleTime);
+void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+u16 ADC_GetConversionValue(ADC_TypeDef* ADCx);
+u32 ADC_GetDualModeConversionValue(void);
+void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, u32 ADC_ExternalTrigInjecConv);
+void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx);
+void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel, u8 Rank, u8 ADC_SampleTime);
+void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, u8 Length);
+void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, u8 ADC_InjectedChannel, u16 Offset);
+u16 ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, u8 ADC_InjectedChannel);
+void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, u32 ADC_AnalogWatchdog);
+void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, u16 HighThreshold, u16 LowThreshold);
+void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel);
+void ADC_TempSensorVrefintCmd(FunctionalState NewState);
+FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, u8 ADC_FLAG);
+void ADC_ClearFlag(ADC_TypeDef* ADCx, u8 ADC_FLAG);
+ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, u16 ADC_IT);
+void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, u16 ADC_IT);
+
+#endif /*__STM32F10x_ADC_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_bkp.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_bkp.h new file mode 100755 index 0000000..3b10ff7 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_bkp.h @@ -0,0 +1,122 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_bkp.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* BKP firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_BKP_H
+#define __STM32F10x_BKP_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Tamper Pin active level */
+#define BKP_TamperPinLevel_High ((u16)0x0000)
+#define BKP_TamperPinLevel_Low ((u16)0x0001)
+
+#define IS_BKP_TAMPER_PIN_LEVEL(LEVEL) (((LEVEL) == BKP_TamperPinLevel_High) || \
+ ((LEVEL) == BKP_TamperPinLevel_Low))
+
+/* RTC output source to output on the Tamper pin */
+#define BKP_RTCOutputSource_None ((u16)0x0000)
+#define BKP_RTCOutputSource_CalibClock ((u16)0x0080)
+#define BKP_RTCOutputSource_Alarm ((u16)0x0100)
+#define BKP_RTCOutputSource_Second ((u16)0x0300)
+
+#define IS_BKP_RTC_OUTPUT_SOURCE(SOURCE) (((SOURCE) == BKP_RTCOutputSource_None) || \
+ ((SOURCE) == BKP_RTCOutputSource_CalibClock) || \
+ ((SOURCE) == BKP_RTCOutputSource_Alarm) || \
+ ((SOURCE) == BKP_RTCOutputSource_Second))
+
+/* Data Backup Register */
+#define BKP_DR1 ((u16)0x0004)
+#define BKP_DR2 ((u16)0x0008)
+#define BKP_DR3 ((u16)0x000C)
+#define BKP_DR4 ((u16)0x0010)
+#define BKP_DR5 ((u16)0x0014)
+#define BKP_DR6 ((u16)0x0018)
+#define BKP_DR7 ((u16)0x001C)
+#define BKP_DR8 ((u16)0x0020)
+#define BKP_DR9 ((u16)0x0024)
+#define BKP_DR10 ((u16)0x0028)
+#define BKP_DR11 ((u16)0x0040)
+#define BKP_DR12 ((u16)0x0044)
+#define BKP_DR13 ((u16)0x0048)
+#define BKP_DR14 ((u16)0x004C)
+#define BKP_DR15 ((u16)0x0050)
+#define BKP_DR16 ((u16)0x0054)
+#define BKP_DR17 ((u16)0x0058)
+#define BKP_DR18 ((u16)0x005C)
+#define BKP_DR19 ((u16)0x0060)
+#define BKP_DR20 ((u16)0x0064)
+#define BKP_DR21 ((u16)0x0068)
+#define BKP_DR22 ((u16)0x006C)
+#define BKP_DR23 ((u16)0x0070)
+#define BKP_DR24 ((u16)0x0074)
+#define BKP_DR25 ((u16)0x0078)
+#define BKP_DR26 ((u16)0x007C)
+#define BKP_DR27 ((u16)0x0080)
+#define BKP_DR28 ((u16)0x0084)
+#define BKP_DR29 ((u16)0x0088)
+#define BKP_DR30 ((u16)0x008C)
+#define BKP_DR31 ((u16)0x0090)
+#define BKP_DR32 ((u16)0x0094)
+#define BKP_DR33 ((u16)0x0098)
+#define BKP_DR34 ((u16)0x009C)
+#define BKP_DR35 ((u16)0x00A0)
+#define BKP_DR36 ((u16)0x00A4)
+#define BKP_DR37 ((u16)0x00A8)
+#define BKP_DR38 ((u16)0x00AC)
+#define BKP_DR39 ((u16)0x00B0)
+#define BKP_DR40 ((u16)0x00B4)
+#define BKP_DR41 ((u16)0x00B8)
+#define BKP_DR42 ((u16)0x00BC)
+
+#define IS_BKP_DR(DR) (((DR) == BKP_DR1) || ((DR) == BKP_DR2) || ((DR) == BKP_DR3) || \
+ ((DR) == BKP_DR4) || ((DR) == BKP_DR5) || ((DR) == BKP_DR6) || \
+ ((DR) == BKP_DR7) || ((DR) == BKP_DR8) || ((DR) == BKP_DR9) || \
+ ((DR) == BKP_DR10) || ((DR) == BKP_DR11) || ((DR) == BKP_DR12) || \
+ ((DR) == BKP_DR13) || ((DR) == BKP_DR14) || ((DR) == BKP_DR15) || \
+ ((DR) == BKP_DR16) || ((DR) == BKP_DR17) || ((DR) == BKP_DR18) || \
+ ((DR) == BKP_DR19) || ((DR) == BKP_DR20) || ((DR) == BKP_DR21) || \
+ ((DR) == BKP_DR22) || ((DR) == BKP_DR23) || ((DR) == BKP_DR24) || \
+ ((DR) == BKP_DR25) || ((DR) == BKP_DR26) || ((DR) == BKP_DR27) || \
+ ((DR) == BKP_DR28) || ((DR) == BKP_DR29) || ((DR) == BKP_DR30) || \
+ ((DR) == BKP_DR31) || ((DR) == BKP_DR32) || ((DR) == BKP_DR33) || \
+ ((DR) == BKP_DR34) || ((DR) == BKP_DR35) || ((DR) == BKP_DR36) || \
+ ((DR) == BKP_DR37) || ((DR) == BKP_DR38) || ((DR) == BKP_DR39) || \
+ ((DR) == BKP_DR40) || ((DR) == BKP_DR41) || ((DR) == BKP_DR42))
+
+#define IS_BKP_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x7F)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void BKP_DeInit(void);
+void BKP_TamperPinLevelConfig(u16 BKP_TamperPinLevel);
+void BKP_TamperPinCmd(FunctionalState NewState);
+void BKP_ITConfig(FunctionalState NewState);
+void BKP_RTCOutputConfig(u16 BKP_RTCOutputSource);
+void BKP_SetRTCCalibrationValue(u8 CalibrationValue);
+void BKP_WriteBackupRegister(u16 BKP_DR, u16 Data);
+u16 BKP_ReadBackupRegister(u16 BKP_DR);
+FlagStatus BKP_GetFlagStatus(void);
+void BKP_ClearFlag(void);
+ITStatus BKP_GetITStatus(void);
+void BKP_ClearITPendingBit(void);
+
+#endif /* __STM32F10x_BKP_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_can.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_can.h new file mode 100755 index 0000000..5d3d40e --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_can.h @@ -0,0 +1,263 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_can.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* CAN firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CAN_H
+#define __STM32F10x_CAN_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* CAN init structure definition */
+typedef struct
+{
+ FunctionalState CAN_TTCM;
+ FunctionalState CAN_ABOM;
+ FunctionalState CAN_AWUM;
+ FunctionalState CAN_NART;
+ FunctionalState CAN_RFLM;
+ FunctionalState CAN_TXFP;
+ u8 CAN_Mode;
+ u8 CAN_SJW;
+ u8 CAN_BS1;
+ u8 CAN_BS2;
+ u16 CAN_Prescaler;
+} CAN_InitTypeDef;
+
+/* CAN filter init structure definition */
+typedef struct
+{
+ u8 CAN_FilterNumber;
+ u8 CAN_FilterMode;
+ u8 CAN_FilterScale;
+ u16 CAN_FilterIdHigh;
+ u16 CAN_FilterIdLow;
+ u16 CAN_FilterMaskIdHigh;
+ u16 CAN_FilterMaskIdLow;
+ u16 CAN_FilterFIFOAssignment;
+ FunctionalState CAN_FilterActivation;
+} CAN_FilterInitTypeDef;
+
+/* CAN Tx message structure definition */
+typedef struct
+{
+ u32 StdId;
+ u32 ExtId;
+ u8 IDE;
+ u8 RTR;
+ u8 DLC;
+ u8 Data[8];
+} CanTxMsg;
+
+/* CAN Rx message structure definition */
+typedef struct
+{
+ u32 StdId;
+ u32 ExtId;
+ u8 IDE;
+ u8 RTR;
+ u8 DLC;
+ u8 Data[8];
+ u8 FMI;
+} CanRxMsg;
+
+/* Exported constants --------------------------------------------------------*/
+
+/* CAN sleep constants */
+#define CANINITFAILED ((u8)0x00) /* CAN initialization failed */
+#define CANINITOK ((u8)0x01) /* CAN initialization failed */
+
+/* CAN operating mode */
+#define CAN_Mode_Normal ((u8)0x00) /* normal mode */
+#define CAN_Mode_LoopBack ((u8)0x01) /* loopback mode */
+#define CAN_Mode_Silent ((u8)0x02) /* silent mode */
+#define CAN_Mode_Silent_LoopBack ((u8)0x03) /* loopback combined with silent mode */
+
+#define IS_CAN_MODE(MODE) (((MODE) == CAN_Mode_Normal) || ((MODE) == CAN_Mode_LoopBack)|| \
+ ((MODE) == CAN_Mode_Silent) || ((MODE) == CAN_Mode_Silent_LoopBack))
+
+/* CAN synchronisation jump width */
+#define CAN_SJW_1tq ((u8)0x00) /* 1 time quantum */
+#define CAN_SJW_2tq ((u8)0x01) /* 2 time quantum */
+#define CAN_SJW_3tq ((u8)0x02) /* 3 time quantum */
+#define CAN_SJW_4tq ((u8)0x03) /* 4 time quantum */
+
+#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1tq) || ((SJW) == CAN_SJW_2tq)|| \
+ ((SJW) == CAN_SJW_3tq) || ((SJW) == CAN_SJW_4tq))
+
+/* time quantum in bit segment 1 */
+#define CAN_BS1_1tq ((u8)0x00) /* 1 time quantum */
+#define CAN_BS1_2tq ((u8)0x01) /* 2 time quantum */
+#define CAN_BS1_3tq ((u8)0x02) /* 3 time quantum */
+#define CAN_BS1_4tq ((u8)0x03) /* 4 time quantum */
+#define CAN_BS1_5tq ((u8)0x04) /* 5 time quantum */
+#define CAN_BS1_6tq ((u8)0x05) /* 6 time quantum */
+#define CAN_BS1_7tq ((u8)0x06) /* 7 time quantum */
+#define CAN_BS1_8tq ((u8)0x07) /* 8 time quantum */
+#define CAN_BS1_9tq ((u8)0x08) /* 9 time quantum */
+#define CAN_BS1_10tq ((u8)0x09) /* 10 time quantum */
+#define CAN_BS1_11tq ((u8)0x0A) /* 11 time quantum */
+#define CAN_BS1_12tq ((u8)0x0B) /* 12 time quantum */
+#define CAN_BS1_13tq ((u8)0x0C) /* 13 time quantum */
+#define CAN_BS1_14tq ((u8)0x0D) /* 14 time quantum */
+#define CAN_BS1_15tq ((u8)0x0E) /* 15 time quantum */
+#define CAN_BS1_16tq ((u8)0x0F) /* 16 time quantum */
+
+#define IS_CAN_BS1(BS1) ((BS1) <= CAN_BS1_16tq)
+
+/* time quantum in bit segment 2 */
+#define CAN_BS2_1tq ((u8)0x00) /* 1 time quantum */
+#define CAN_BS2_2tq ((u8)0x01) /* 2 time quantum */
+#define CAN_BS2_3tq ((u8)0x02) /* 3 time quantum */
+#define CAN_BS2_4tq ((u8)0x03) /* 4 time quantum */
+#define CAN_BS2_5tq ((u8)0x04) /* 5 time quantum */
+#define CAN_BS2_6tq ((u8)0x05) /* 6 time quantum */
+#define CAN_BS2_7tq ((u8)0x06) /* 7 time quantum */
+#define CAN_BS2_8tq ((u8)0x07) /* 8 time quantum */
+
+#define IS_CAN_BS2(BS2) ((BS2) <= CAN_BS2_8tq)
+
+/* CAN clock prescaler */
+#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1) && ((PRESCALER) <= 1024))
+
+/* CAN filter number */
+#define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 13)
+
+/* CAN filter mode */
+#define CAN_FilterMode_IdMask ((u8)0x00) /* id/mask mode */
+#define CAN_FilterMode_IdList ((u8)0x01) /* identifier list mode */
+
+#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FilterMode_IdMask) || \
+ ((MODE) == CAN_FilterMode_IdList))
+
+/* CAN filter scale */
+#define CAN_FilterScale_16bit ((u8)0x00) /* 16-bit filter scale */
+#define CAN_FilterScale_32bit ((u8)0x01) /* 2-bit filter scale */
+
+#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FilterScale_16bit) || \
+ ((SCALE) == CAN_FilterScale_32bit))
+
+/* CAN filter FIFO assignation */
+#define CAN_FilterFIFO0 ((u8)0x00) /* Filter FIFO 0 assignment for filter x */
+#define CAN_FilterFIFO1 ((u8)0x01) /* Filter FIFO 1 assignment for filter x */
+
+#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FilterFIFO0) || \
+ ((FIFO) == CAN_FilterFIFO1))
+
+/* CAN Tx */
+#define IS_CAN_TRANSMITMAILBOX(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= ((u8)0x02))
+#define IS_CAN_STDID(STDID) ((STDID) <= ((u32)0x7FF))
+#define IS_CAN_EXTID(EXTID) ((EXTID) <= ((u32)0x1FFFFFFF))
+#define IS_CAN_DLC(DLC) ((DLC) <= ((u8)0x08))
+
+/* CAN identifier type */
+#define CAN_ID_STD ((u32)0x00000000) /* Standard Id */
+#define CAN_ID_EXT ((u32)0x00000004) /* Extended Id */
+
+#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_ID_STD) || ((IDTYPE) == CAN_ID_EXT))
+
+/* CAN remote transmission request */
+#define CAN_RTR_DATA ((u32)0x00000000) /* Data frame */
+#define CAN_RTR_REMOTE ((u32)0x00000002) /* Remote frame */
+
+#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_DATA) || ((RTR) == CAN_RTR_REMOTE))
+
+/* CAN transmit constants */
+#define CANTXFAILED ((u8)0x00) /* CAN transmission failed */
+#define CANTXOK ((u8)0x01) /* CAN transmission succeeded */
+#define CANTXPENDING ((u8)0x02) /* CAN transmission pending */
+#define CAN_NO_MB ((u8)0x04) /* CAN cell did not provide an empty mailbox */
+
+/* CAN receive FIFO number constants */
+#define CAN_FIFO0 ((u8)0x00) /* CAN FIFO0 used to receive */
+#define CAN_FIFO1 ((u8)0x01) /* CAN FIFO1 used to receive */
+
+#define IS_CAN_FIFO(FIFO) (((FIFO) == CAN_FIFO0) || ((FIFO) == CAN_FIFO1))
+
+/* CAN sleep constants */
+#define CANSLEEPFAILED ((u8)0x00) /* CAN did not enter the sleep mode */
+#define CANSLEEPOK ((u8)0x01) /* CAN entered the sleep mode */
+
+/* CAN wake up constants */
+#define CANWAKEUPFAILED ((u8)0x00) /* CAN did not leave the sleep mode */
+#define CANWAKEUPOK ((u8)0x01) /* CAN leaved the sleep mode */
+
+/* CAN flags */
+#define CAN_FLAG_EWG ((u32)0x00000001) /* Error Warning Flag */
+#define CAN_FLAG_EPV ((u32)0x00000002) /* Error Passive Flag */
+#define CAN_FLAG_BOF ((u32)0x00000004) /* Bus-Off Flag */
+
+#define IS_CAN_FLAG(FLAG) (((FLAG) == CAN_FLAG_EWG) || ((FLAG) == CAN_FLAG_EPV) ||\
+ ((FLAG) == CAN_FLAG_BOF))
+
+/* CAN interrupts */
+#define CAN_IT_RQCP0 ((u32)0x00000005) /* Request completed mailbox 0 */
+#define CAN_IT_RQCP1 ((u32)0x00000006) /* Request completed mailbox 1 */
+#define CAN_IT_RQCP2 ((u32)0x00000007) /* Request completed mailbox 2 */
+#define CAN_IT_TME ((u32)0x00000001) /* Transmit mailbox empty */
+#define CAN_IT_FMP0 ((u32)0x00000002) /* FIFO 0 message pending */
+#define CAN_IT_FF0 ((u32)0x00000004) /* FIFO 0 full */
+#define CAN_IT_FOV0 ((u32)0x00000008) /* FIFO 0 overrun */
+#define CAN_IT_FMP1 ((u32)0x00000010) /* FIFO 1 message pending */
+#define CAN_IT_FF1 ((u32)0x00000020) /* FIFO 1 full */
+#define CAN_IT_FOV1 ((u32)0x00000040) /* FIFO 1 overrun */
+#define CAN_IT_EWG ((u32)0x00000100) /* Error warning */
+#define CAN_IT_EPV ((u32)0x00000200) /* Error passive */
+#define CAN_IT_BOF ((u32)0x00000400) /* Bus-off */
+#define CAN_IT_LEC ((u32)0x00000800) /* Last error code */
+#define CAN_IT_ERR ((u32)0x00008000) /* Error */
+#define CAN_IT_WKU ((u32)0x00010000) /* Wake-up */
+#define CAN_IT_SLK ((u32)0x00020000) /* Sleep */
+
+#define IS_CAN_ITConfig(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FMP0) ||\
+ ((IT) == CAN_IT_FF0) || ((IT) == CAN_IT_FOV0) ||\
+ ((IT) == CAN_IT_FMP1) || ((IT) == CAN_IT_FF1) ||\
+ ((IT) == CAN_IT_FOV1) || ((IT) == CAN_IT_EWG) ||\
+ ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\
+ ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\
+ ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK))
+
+#define IS_CAN_ITStatus(IT) (((IT) == CAN_IT_RQCP0) || ((IT) == CAN_IT_RQCP1) ||\
+ ((IT) == CAN_IT_RQCP2) || ((IT) == CAN_IT_FF0) ||\
+ ((IT) == CAN_IT_FOV0) || ((IT) == CAN_IT_FF1) ||\
+ ((IT) == CAN_IT_FOV1) || ((IT) == CAN_IT_EWG) ||\
+ ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\
+ ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported function protypes ----------------------------------------------- */
+void CAN_DeInit(void);
+u8 CAN_Init(CAN_InitTypeDef* CAN_InitStruct);
+void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct);
+void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct);
+void CAN_ITConfig(u32 CAN_IT, FunctionalState NewState);
+u8 CAN_Transmit(CanTxMsg* TxMessage);
+u8 CAN_TransmitStatus(u8 TransmitMailbox);
+void CAN_CancelTransmit(u8 Mailbox);
+void CAN_FIFORelease(u8 FIFONumber);
+u8 CAN_MessagePending(u8 FIFONumber);
+void CAN_Receive(u8 FIFONumber, CanRxMsg* RxMessage);
+u8 CAN_Sleep(void);
+u8 CAN_WakeUp(void);
+FlagStatus CAN_GetFlagStatus(u32 CAN_FLAG);
+void CAN_ClearFlag(u32 CAN_FLAG);
+ITStatus CAN_GetITStatus(u32 CAN_IT);
+void CAN_ClearITPendingBit(u32 CAN_IT);
+
+#endif /* __STM32F10x_CAN_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_crc.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_crc.h new file mode 100755 index 0000000..edeef36 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_crc.h @@ -0,0 +1,37 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_crc.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* CRC firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CRC_H
+#define __STM32F10x_CRC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void CRC_ResetDR(void);
+u32 CRC_CalcCRC(u32 Data);
+u32 CRC_CalcBlockCRC(u32 pBuffer[], u32 BufferLength);
+u32 CRC_GetCRC(void);
+void CRC_SetIDRegister(u8 IDValue);
+u8 CRC_GetIDRegister(void);
+
+#endif /* __STM32F10x_CRC_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_dac.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_dac.h new file mode 100755 index 0000000..98c1642 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_dac.h @@ -0,0 +1,167 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_dac.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* DAC firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_DAC_H
+#define __STM32F10x_DAC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* DAC Init structure definition */
+typedef struct
+{
+ u32 DAC_Trigger;
+ u32 DAC_WaveGeneration;
+ u32 DAC_LFSRUnmask_TriangleAmplitude;
+ u32 DAC_OutputBuffer;
+}DAC_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+/* DAC trigger selection */
+#define DAC_Trigger_None ((u32)0x00000000)
+#define DAC_Trigger_T6_TRGO ((u32)0x00000004)
+#define DAC_Trigger_T8_TRGO ((u32)0x0000000C)
+#define DAC_Trigger_T7_TRGO ((u32)0x00000014)
+#define DAC_Trigger_T5_TRGO ((u32)0x0000001C)
+#define DAC_Trigger_T2_TRGO ((u32)0x00000024)
+#define DAC_Trigger_T4_TRGO ((u32)0x0000002C)
+#define DAC_Trigger_Ext_IT9 ((u32)0x00000034)
+#define DAC_Trigger_Software ((u32)0x0000003C)
+
+#define IS_DAC_TRIGGER(TRIGGER) (((TRIGGER) == DAC_Trigger_None) || \
+ ((TRIGGER) == DAC_Trigger_T6_TRGO) || \
+ ((TRIGGER) == DAC_Trigger_T8_TRGO) || \
+ ((TRIGGER) == DAC_Trigger_T7_TRGO) || \
+ ((TRIGGER) == DAC_Trigger_T5_TRGO) || \
+ ((TRIGGER) == DAC_Trigger_T2_TRGO) || \
+ ((TRIGGER) == DAC_Trigger_T4_TRGO) || \
+ ((TRIGGER) == DAC_Trigger_Ext_IT9) || \
+ ((TRIGGER) == DAC_Trigger_Software))
+
+/* DAC wave generation */
+#define DAC_WaveGeneration_None ((u32)0x00000000)
+#define DAC_WaveGeneration_Noise ((u32)0x00000040)
+#define DAC_WaveGeneration_Triangle ((u32)0x00000080)
+
+#define IS_DAC_GENERATE_WAVE(WAVE) (((WAVE) == DAC_WaveGeneration_None) || \
+ ((WAVE) == DAC_WaveGeneration_Noise) || \
+ ((WAVE) == DAC_WaveGeneration_Triangle))
+
+/* DAC noise wave generation mask / triangle wave generation max amplitude */
+#define DAC_LFSRUnmask_Bit0 ((u32)0x00000000)
+#define DAC_LFSRUnmask_Bits1_0 ((u32)0x00000100)
+#define DAC_LFSRUnmask_Bits2_0 ((u32)0x00000200)
+#define DAC_LFSRUnmask_Bits3_0 ((u32)0x00000300)
+#define DAC_LFSRUnmask_Bits4_0 ((u32)0x00000400)
+#define DAC_LFSRUnmask_Bits5_0 ((u32)0x00000500)
+#define DAC_LFSRUnmask_Bits6_0 ((u32)0x00000600)
+#define DAC_LFSRUnmask_Bits7_0 ((u32)0x00000700)
+#define DAC_LFSRUnmask_Bits8_0 ((u32)0x00000800)
+#define DAC_LFSRUnmask_Bits9_0 ((u32)0x00000900)
+#define DAC_LFSRUnmask_Bits10_0 ((u32)0x00000A00)
+#define DAC_LFSRUnmask_Bits11_0 ((u32)0x00000B00)
+
+#define DAC_TriangleAmplitude_1 ((u32)0x00000000)
+#define DAC_TriangleAmplitude_3 ((u32)0x00000100)
+#define DAC_TriangleAmplitude_7 ((u32)0x00000200)
+#define DAC_TriangleAmplitude_15 ((u32)0x00000300)
+#define DAC_TriangleAmplitude_31 ((u32)0x00000400)
+#define DAC_TriangleAmplitude_63 ((u32)0x00000500)
+#define DAC_TriangleAmplitude_127 ((u32)0x00000600)
+#define DAC_TriangleAmplitude_255 ((u32)0x00000700)
+#define DAC_TriangleAmplitude_511 ((u32)0x00000800)
+#define DAC_TriangleAmplitude_1023 ((u32)0x00000900)
+#define DAC_TriangleAmplitude_2047 ((u32)0x00000A00)
+#define DAC_TriangleAmplitude_4095 ((u32)0x00000B00)
+
+#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUnmask_Bit0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits1_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits2_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits3_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits4_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits5_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits6_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits7_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits8_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits9_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits10_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits11_0) || \
+ ((VALUE) == DAC_TriangleAmplitude_1) || \
+ ((VALUE) == DAC_TriangleAmplitude_3) || \
+ ((VALUE) == DAC_TriangleAmplitude_7) || \
+ ((VALUE) == DAC_TriangleAmplitude_15) || \
+ ((VALUE) == DAC_TriangleAmplitude_31) || \
+ ((VALUE) == DAC_TriangleAmplitude_63) || \
+ ((VALUE) == DAC_TriangleAmplitude_127) || \
+ ((VALUE) == DAC_TriangleAmplitude_255) || \
+ ((VALUE) == DAC_TriangleAmplitude_511) || \
+ ((VALUE) == DAC_TriangleAmplitude_1023) || \
+ ((VALUE) == DAC_TriangleAmplitude_2047) || \
+ ((VALUE) == DAC_TriangleAmplitude_4095))
+
+/* DAC output buffer */
+#define DAC_OutputBuffer_Enable ((u32)0x00000000)
+#define DAC_OutputBuffer_Disable ((u32)0x00000002)
+
+#define IS_DAC_OUTPUT_BUFFER_STATE(STATE) (((STATE) == DAC_OutputBuffer_Enable) || \
+ ((STATE) == DAC_OutputBuffer_Disable))
+
+/* DAC Channel selection */
+#define DAC_Channel_1 ((u32)0x00000000)
+#define DAC_Channel_2 ((u32)0x00000010)
+
+#define IS_DAC_CHANNEL(CHANNEL) (((CHANNEL) == DAC_Channel_1) || \
+ ((CHANNEL) == DAC_Channel_2))
+
+/* DAC data alignement */
+#define DAC_Align_12b_R ((u32)0x00000000)
+#define DAC_Align_12b_L ((u32)0x00000004)
+#define DAC_Align_8b_R ((u32)0x00000008)
+
+#define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_Align_12b_R) || \
+ ((ALIGN) == DAC_Align_12b_L) || \
+ ((ALIGN) == DAC_Align_8b_R))
+
+/* DAC wave generation */
+#define DAC_Wave_Noise ((u32)0x00000040)
+#define DAC_Wave_Triangle ((u32)0x00000080)
+
+#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_Wave_Noise) || \
+ ((WAVE) == DAC_Wave_Triangle))
+
+/* DAC data ------------------------------------------------------------------*/
+#define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+void DAC_DeInit(void);
+void DAC_Init(u32 DAC_Channel, DAC_InitTypeDef* DAC_InitStruct);
+void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct);
+void DAC_Cmd(u32 DAC_Channel, FunctionalState NewState);
+void DAC_DMACmd(u32 DAC_Channel, FunctionalState NewState);
+void DAC_SoftwareTriggerCmd(u32 DAC_Channel, FunctionalState NewState);
+void DAC_DualSoftwareTriggerCmd(FunctionalState NewState);
+void DAC_WaveGenerationCmd(u32 DAC_Channel, u32 DAC_Wave, FunctionalState NewState);
+void DAC_SetChannel1Data(u32 DAC_Align, u16 Data);
+void DAC_SetChannel2Data(u32 DAC_Align, u16 Data);
+void DAC_SetDualChannelData(u32 DAC_Align, u16 Data2, u16 Data1);
+u16 DAC_GetDataOutputValue(u32 DAC_Channel);
+
+#endif /*__STM32F10x_DAC_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_dbgmcu.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_dbgmcu.h new file mode 100755 index 0000000..440f07f --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_dbgmcu.h @@ -0,0 +1,55 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_dbgmcu.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* DBGMCU firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_DBGMCU_H
+#define __STM32F10x_DBGMCU_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+#define DBGMCU_SLEEP ((u32)0x00000001)
+#define DBGMCU_STOP ((u32)0x00000002)
+#define DBGMCU_STANDBY ((u32)0x00000004)
+#define DBGMCU_IWDG_STOP ((u32)0x00000100)
+#define DBGMCU_WWDG_STOP ((u32)0x00000200)
+#define DBGMCU_TIM1_STOP ((u32)0x00000400)
+#define DBGMCU_TIM2_STOP ((u32)0x00000800)
+#define DBGMCU_TIM3_STOP ((u32)0x00001000)
+#define DBGMCU_TIM4_STOP ((u32)0x00002000)
+#define DBGMCU_CAN_STOP ((u32)0x00004000)
+#define DBGMCU_I2C1_SMBUS_TIMEOUT ((u32)0x00008000)
+#define DBGMCU_I2C2_SMBUS_TIMEOUT ((u32)0x00010000)
+#define DBGMCU_TIM5_STOP ((u32)0x00020000)
+#define DBGMCU_TIM6_STOP ((u32)0x00040000)
+#define DBGMCU_TIM7_STOP ((u32)0x00080000)
+#define DBGMCU_TIM8_STOP ((u32)0x00100000)
+
+#define IS_DBGMCU_PERIPH(PERIPH) ((((PERIPH) & 0xFFE000F8) == 0x00) && ((PERIPH) != 0x00))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+u32 DBGMCU_GetREVID(void);
+u32 DBGMCU_GetDEVID(void);
+void DBGMCU_Config(u32 DBGMCU_Periph, FunctionalState NewState);
+
+#endif /* __STM32F10x_DBGMCU_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
+
+
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_dma.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_dma.h new file mode 100755 index 0000000..7ed4969 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_dma.h @@ -0,0 +1,297 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_dma.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* DMA firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_DMA_H
+#define __STM32F10x_DMA_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* DMA Init structure definition */
+typedef struct
+{
+ u32 DMA_PeripheralBaseAddr;
+ u32 DMA_MemoryBaseAddr;
+ u32 DMA_DIR;
+ u32 DMA_BufferSize;
+ u32 DMA_PeripheralInc;
+ u32 DMA_MemoryInc;
+ u32 DMA_PeripheralDataSize;
+ u32 DMA_MemoryDataSize;
+ u32 DMA_Mode;
+ u32 DMA_Priority;
+ u32 DMA_M2M;
+}DMA_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+#define IS_DMA_ALL_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == DMA1_Channel1_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA1_Channel2_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA1_Channel3_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA1_Channel4_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA1_Channel5_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA1_Channel6_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA1_Channel7_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA2_Channel1_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA2_Channel2_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA2_Channel3_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA2_Channel4_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA2_Channel5_BASE))
+
+/* DMA data transfer direction -----------------------------------------------*/
+#define DMA_DIR_PeripheralDST ((u32)0x00000010)
+#define DMA_DIR_PeripheralSRC ((u32)0x00000000)
+
+#define IS_DMA_DIR(DIR) (((DIR) == DMA_DIR_PeripheralDST) || \
+ ((DIR) == DMA_DIR_PeripheralSRC))
+
+/* DMA peripheral incremented mode -------------------------------------------*/
+#define DMA_PeripheralInc_Enable ((u32)0x00000040)
+#define DMA_PeripheralInc_Disable ((u32)0x00000000)
+
+#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PeripheralInc_Enable) || \
+ ((STATE) == DMA_PeripheralInc_Disable))
+
+/* DMA memory incremented mode -----------------------------------------------*/
+#define DMA_MemoryInc_Enable ((u32)0x00000080)
+#define DMA_MemoryInc_Disable ((u32)0x00000000)
+
+#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MemoryInc_Enable) || \
+ ((STATE) == DMA_MemoryInc_Disable))
+
+/* DMA peripheral data size --------------------------------------------------*/
+#define DMA_PeripheralDataSize_Byte ((u32)0x00000000)
+#define DMA_PeripheralDataSize_HalfWord ((u32)0x00000100)
+#define DMA_PeripheralDataSize_Word ((u32)0x00000200)
+
+#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PeripheralDataSize_Byte) || \
+ ((SIZE) == DMA_PeripheralDataSize_HalfWord) || \
+ ((SIZE) == DMA_PeripheralDataSize_Word))
+
+/* DMA memory data size ------------------------------------------------------*/
+#define DMA_MemoryDataSize_Byte ((u32)0x00000000)
+#define DMA_MemoryDataSize_HalfWord ((u32)0x00000400)
+#define DMA_MemoryDataSize_Word ((u32)0x00000800)
+
+#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MemoryDataSize_Byte) || \
+ ((SIZE) == DMA_MemoryDataSize_HalfWord) || \
+ ((SIZE) == DMA_MemoryDataSize_Word))
+
+/* DMA circular/normal mode --------------------------------------------------*/
+#define DMA_Mode_Circular ((u32)0x00000020)
+#define DMA_Mode_Normal ((u32)0x00000000)
+
+#define IS_DMA_MODE(MODE) (((MODE) == DMA_Mode_Circular) || ((MODE) == DMA_Mode_Normal))
+
+/* DMA priority level --------------------------------------------------------*/
+#define DMA_Priority_VeryHigh ((u32)0x00003000)
+#define DMA_Priority_High ((u32)0x00002000)
+#define DMA_Priority_Medium ((u32)0x00001000)
+#define DMA_Priority_Low ((u32)0x00000000)
+
+#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_Priority_VeryHigh) || \
+ ((PRIORITY) == DMA_Priority_High) || \
+ ((PRIORITY) == DMA_Priority_Medium) || \
+ ((PRIORITY) == DMA_Priority_Low))
+
+/* DMA memory to memory ------------------------------------------------------*/
+#define DMA_M2M_Enable ((u32)0x00004000)
+#define DMA_M2M_Disable ((u32)0x00000000)
+
+#define IS_DMA_M2M_STATE(STATE) (((STATE) == DMA_M2M_Enable) || ((STATE) == DMA_M2M_Disable))
+
+/* DMA interrupts definition -------------------------------------------------*/
+#define DMA_IT_TC ((u32)0x00000002)
+#define DMA_IT_HT ((u32)0x00000004)
+#define DMA_IT_TE ((u32)0x00000008)
+
+#define IS_DMA_CONFIG_IT(IT) ((((IT) & 0xFFFFFFF1) == 0x00) && ((IT) != 0x00))
+
+/* For DMA1 */
+#define DMA1_IT_GL1 ((u32)0x00000001)
+#define DMA1_IT_TC1 ((u32)0x00000002)
+#define DMA1_IT_HT1 ((u32)0x00000004)
+#define DMA1_IT_TE1 ((u32)0x00000008)
+#define DMA1_IT_GL2 ((u32)0x00000010)
+#define DMA1_IT_TC2 ((u32)0x00000020)
+#define DMA1_IT_HT2 ((u32)0x00000040)
+#define DMA1_IT_TE2 ((u32)0x00000080)
+#define DMA1_IT_GL3 ((u32)0x00000100)
+#define DMA1_IT_TC3 ((u32)0x00000200)
+#define DMA1_IT_HT3 ((u32)0x00000400)
+#define DMA1_IT_TE3 ((u32)0x00000800)
+#define DMA1_IT_GL4 ((u32)0x00001000)
+#define DMA1_IT_TC4 ((u32)0x00002000)
+#define DMA1_IT_HT4 ((u32)0x00004000)
+#define DMA1_IT_TE4 ((u32)0x00008000)
+#define DMA1_IT_GL5 ((u32)0x00010000)
+#define DMA1_IT_TC5 ((u32)0x00020000)
+#define DMA1_IT_HT5 ((u32)0x00040000)
+#define DMA1_IT_TE5 ((u32)0x00080000)
+#define DMA1_IT_GL6 ((u32)0x00100000)
+#define DMA1_IT_TC6 ((u32)0x00200000)
+#define DMA1_IT_HT6 ((u32)0x00400000)
+#define DMA1_IT_TE6 ((u32)0x00800000)
+#define DMA1_IT_GL7 ((u32)0x01000000)
+#define DMA1_IT_TC7 ((u32)0x02000000)
+#define DMA1_IT_HT7 ((u32)0x04000000)
+#define DMA1_IT_TE7 ((u32)0x08000000)
+/* For DMA2 */
+#define DMA2_IT_GL1 ((u32)0x10000001)
+#define DMA2_IT_TC1 ((u32)0x10000002)
+#define DMA2_IT_HT1 ((u32)0x10000004)
+#define DMA2_IT_TE1 ((u32)0x10000008)
+#define DMA2_IT_GL2 ((u32)0x10000010)
+#define DMA2_IT_TC2 ((u32)0x10000020)
+#define DMA2_IT_HT2 ((u32)0x10000040)
+#define DMA2_IT_TE2 ((u32)0x10000080)
+#define DMA2_IT_GL3 ((u32)0x10000100)
+#define DMA2_IT_TC3 ((u32)0x10000200)
+#define DMA2_IT_HT3 ((u32)0x10000400)
+#define DMA2_IT_TE3 ((u32)0x10000800)
+#define DMA2_IT_GL4 ((u32)0x10001000)
+#define DMA2_IT_TC4 ((u32)0x10002000)
+#define DMA2_IT_HT4 ((u32)0x10004000)
+#define DMA2_IT_TE4 ((u32)0x10008000)
+#define DMA2_IT_GL5 ((u32)0x10010000)
+#define DMA2_IT_TC5 ((u32)0x10020000)
+#define DMA2_IT_HT5 ((u32)0x10040000)
+#define DMA2_IT_TE5 ((u32)0x10080000)
+
+#define IS_DMA_CLEAR_IT(IT) (((((IT) & 0xF0000000) == 0x00) || (((IT) & 0xEFF00000) == 0x00)) && ((IT) != 0x00))
+#define IS_DMA_GET_IT(IT) (((IT) == DMA1_IT_GL1) || ((IT) == DMA1_IT_TC1) || \
+ ((IT) == DMA1_IT_HT1) || ((IT) == DMA1_IT_TE1) || \
+ ((IT) == DMA1_IT_GL2) || ((IT) == DMA1_IT_TC2) || \
+ ((IT) == DMA1_IT_HT2) || ((IT) == DMA1_IT_TE2) || \
+ ((IT) == DMA1_IT_GL3) || ((IT) == DMA1_IT_TC3) || \
+ ((IT) == DMA1_IT_HT3) || ((IT) == DMA1_IT_TE3) || \
+ ((IT) == DMA1_IT_GL4) || ((IT) == DMA1_IT_TC4) || \
+ ((IT) == DMA1_IT_HT4) || ((IT) == DMA1_IT_TE4) || \
+ ((IT) == DMA1_IT_GL5) || ((IT) == DMA1_IT_TC5) || \
+ ((IT) == DMA1_IT_HT5) || ((IT) == DMA1_IT_TE5) || \
+ ((IT) == DMA1_IT_GL6) || ((IT) == DMA1_IT_TC6) || \
+ ((IT) == DMA1_IT_HT6) || ((IT) == DMA1_IT_TE6) || \
+ ((IT) == DMA1_IT_GL7) || ((IT) == DMA1_IT_TC7) || \
+ ((IT) == DMA1_IT_HT7) || ((IT) == DMA1_IT_TE7) || \
+ ((IT) == DMA2_IT_GL1) || ((IT) == DMA2_IT_TC1) || \
+ ((IT) == DMA2_IT_HT1) || ((IT) == DMA2_IT_TE1) || \
+ ((IT) == DMA2_IT_GL2) || ((IT) == DMA2_IT_TC2) || \
+ ((IT) == DMA2_IT_HT2) || ((IT) == DMA2_IT_TE2) || \
+ ((IT) == DMA2_IT_GL3) || ((IT) == DMA2_IT_TC3) || \
+ ((IT) == DMA2_IT_HT3) || ((IT) == DMA2_IT_TE3) || \
+ ((IT) == DMA2_IT_GL4) || ((IT) == DMA2_IT_TC4) || \
+ ((IT) == DMA2_IT_HT4) || ((IT) == DMA2_IT_TE4) || \
+ ((IT) == DMA2_IT_GL5) || ((IT) == DMA2_IT_TC5) || \
+ ((IT) == DMA2_IT_HT5) || ((IT) == DMA2_IT_TE5))
+
+/* DMA flags definition ------------------------------------------------------*/
+/* For DMA1 */
+#define DMA1_FLAG_GL1 ((u32)0x00000001)
+#define DMA1_FLAG_TC1 ((u32)0x00000002)
+#define DMA1_FLAG_HT1 ((u32)0x00000004)
+#define DMA1_FLAG_TE1 ((u32)0x00000008)
+#define DMA1_FLAG_GL2 ((u32)0x00000010)
+#define DMA1_FLAG_TC2 ((u32)0x00000020)
+#define DMA1_FLAG_HT2 ((u32)0x00000040)
+#define DMA1_FLAG_TE2 ((u32)0x00000080)
+#define DMA1_FLAG_GL3 ((u32)0x00000100)
+#define DMA1_FLAG_TC3 ((u32)0x00000200)
+#define DMA1_FLAG_HT3 ((u32)0x00000400)
+#define DMA1_FLAG_TE3 ((u32)0x00000800)
+#define DMA1_FLAG_GL4 ((u32)0x00001000)
+#define DMA1_FLAG_TC4 ((u32)0x00002000)
+#define DMA1_FLAG_HT4 ((u32)0x00004000)
+#define DMA1_FLAG_TE4 ((u32)0x00008000)
+#define DMA1_FLAG_GL5 ((u32)0x00010000)
+#define DMA1_FLAG_TC5 ((u32)0x00020000)
+#define DMA1_FLAG_HT5 ((u32)0x00040000)
+#define DMA1_FLAG_TE5 ((u32)0x00080000)
+#define DMA1_FLAG_GL6 ((u32)0x00100000)
+#define DMA1_FLAG_TC6 ((u32)0x00200000)
+#define DMA1_FLAG_HT6 ((u32)0x00400000)
+#define DMA1_FLAG_TE6 ((u32)0x00800000)
+#define DMA1_FLAG_GL7 ((u32)0x01000000)
+#define DMA1_FLAG_TC7 ((u32)0x02000000)
+#define DMA1_FLAG_HT7 ((u32)0x04000000)
+#define DMA1_FLAG_TE7 ((u32)0x08000000)
+/* For DMA2 */
+#define DMA2_FLAG_GL1 ((u32)0x10000001)
+#define DMA2_FLAG_TC1 ((u32)0x10000002)
+#define DMA2_FLAG_HT1 ((u32)0x10000004)
+#define DMA2_FLAG_TE1 ((u32)0x10000008)
+#define DMA2_FLAG_GL2 ((u32)0x10000010)
+#define DMA2_FLAG_TC2 ((u32)0x10000020)
+#define DMA2_FLAG_HT2 ((u32)0x10000040)
+#define DMA2_FLAG_TE2 ((u32)0x10000080)
+#define DMA2_FLAG_GL3 ((u32)0x10000100)
+#define DMA2_FLAG_TC3 ((u32)0x10000200)
+#define DMA2_FLAG_HT3 ((u32)0x10000400)
+#define DMA2_FLAG_TE3 ((u32)0x10000800)
+#define DMA2_FLAG_GL4 ((u32)0x10001000)
+#define DMA2_FLAG_TC4 ((u32)0x10002000)
+#define DMA2_FLAG_HT4 ((u32)0x10004000)
+#define DMA2_FLAG_TE4 ((u32)0x10008000)
+#define DMA2_FLAG_GL5 ((u32)0x10010000)
+#define DMA2_FLAG_TC5 ((u32)0x10020000)
+#define DMA2_FLAG_HT5 ((u32)0x10040000)
+#define DMA2_FLAG_TE5 ((u32)0x10080000)
+
+#define IS_DMA_CLEAR_FLAG(FLAG) (((((FLAG) & 0xF0000000) == 0x00) || (((FLAG) & 0xEFF00000) == 0x00)) && ((FLAG) != 0x00))
+#define IS_DMA_GET_FLAG(FLAG) (((FLAG) == DMA1_FLAG_GL1) || ((FLAG) == DMA1_FLAG_TC1) || \
+ ((FLAG) == DMA1_FLAG_HT1) || ((FLAG) == DMA1_FLAG_TE1) || \
+ ((FLAG) == DMA1_FLAG_GL2) || ((FLAG) == DMA1_FLAG_TC2) || \
+ ((FLAG) == DMA1_FLAG_HT2) || ((FLAG) == DMA1_FLAG_TE2) || \
+ ((FLAG) == DMA1_FLAG_GL3) || ((FLAG) == DMA1_FLAG_TC3) || \
+ ((FLAG) == DMA1_FLAG_HT3) || ((FLAG) == DMA1_FLAG_TE3) || \
+ ((FLAG) == DMA1_FLAG_GL4) || ((FLAG) == DMA1_FLAG_TC4) || \
+ ((FLAG) == DMA1_FLAG_HT4) || ((FLAG) == DMA1_FLAG_TE4) || \
+ ((FLAG) == DMA1_FLAG_GL5) || ((FLAG) == DMA1_FLAG_TC5) || \
+ ((FLAG) == DMA1_FLAG_HT5) || ((FLAG) == DMA1_FLAG_TE5) || \
+ ((FLAG) == DMA1_FLAG_GL6) || ((FLAG) == DMA1_FLAG_TC6) || \
+ ((FLAG) == DMA1_FLAG_HT6) || ((FLAG) == DMA1_FLAG_TE6) || \
+ ((FLAG) == DMA1_FLAG_GL7) || ((FLAG) == DMA1_FLAG_TC7) || \
+ ((FLAG) == DMA1_FLAG_HT7) || ((FLAG) == DMA1_FLAG_TE7) || \
+ ((FLAG) == DMA2_FLAG_GL1) || ((FLAG) == DMA2_FLAG_TC1) || \
+ ((FLAG) == DMA2_FLAG_HT1) || ((FLAG) == DMA2_FLAG_TE1) || \
+ ((FLAG) == DMA2_FLAG_GL2) || ((FLAG) == DMA2_FLAG_TC2) || \
+ ((FLAG) == DMA2_FLAG_HT2) || ((FLAG) == DMA2_FLAG_TE2) || \
+ ((FLAG) == DMA2_FLAG_GL3) || ((FLAG) == DMA2_FLAG_TC3) || \
+ ((FLAG) == DMA2_FLAG_HT3) || ((FLAG) == DMA2_FLAG_TE3) || \
+ ((FLAG) == DMA2_FLAG_GL4) || ((FLAG) == DMA2_FLAG_TC4) || \
+ ((FLAG) == DMA2_FLAG_HT4) || ((FLAG) == DMA2_FLAG_TE4) || \
+ ((FLAG) == DMA2_FLAG_GL5) || ((FLAG) == DMA2_FLAG_TC5) || \
+ ((FLAG) == DMA2_FLAG_HT5) || ((FLAG) == DMA2_FLAG_TE5))
+
+/* DMA Buffer Size -----------------------------------------------------------*/
+#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x1) && ((SIZE) < 0x10000))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx);
+void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct);
+void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct);
+void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState);
+void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, u32 DMA_IT, FunctionalState NewState);
+u16 DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx);
+FlagStatus DMA_GetFlagStatus(u32 DMA_FLAG);
+void DMA_ClearFlag(u32 DMA_FLAG);
+ITStatus DMA_GetITStatus(u32 DMA_IT);
+void DMA_ClearITPendingBit(u32 DMA_IT);
+
+#endif /*__STM32F10x_DMA_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_exti.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_exti.h new file mode 100755 index 0000000..efbedf3 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_exti.h @@ -0,0 +1,107 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_exti.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* EXTI firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_EXTI_H
+#define __STM32F10x_EXTI_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* EXTI mode enumeration -----------------------------------------------------*/
+typedef enum
+{
+ EXTI_Mode_Interrupt = 0x00,
+ EXTI_Mode_Event = 0x04
+}EXTIMode_TypeDef;
+
+#define IS_EXTI_MODE(MODE) (((MODE) == EXTI_Mode_Interrupt) || ((MODE) == EXTI_Mode_Event))
+
+/* EXTI Trigger enumeration --------------------------------------------------*/
+typedef enum
+{
+ EXTI_Trigger_Rising = 0x08,
+ EXTI_Trigger_Falling = 0x0C,
+ EXTI_Trigger_Rising_Falling = 0x10
+}EXTITrigger_TypeDef;
+
+#define IS_EXTI_TRIGGER(TRIGGER) (((TRIGGER) == EXTI_Trigger_Rising) || \
+ ((TRIGGER) == EXTI_Trigger_Falling) || \
+ ((TRIGGER) == EXTI_Trigger_Rising_Falling))
+
+/* EXTI Init Structure definition --------------------------------------------*/
+typedef struct
+{
+ u32 EXTI_Line;
+ EXTIMode_TypeDef EXTI_Mode;
+ EXTITrigger_TypeDef EXTI_Trigger;
+ FunctionalState EXTI_LineCmd;
+}EXTI_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+/* EXTI Lines ----------------------------------------------------------------*/
+#define EXTI_Line0 ((u32)0x00001) /* External interrupt line 0 */
+#define EXTI_Line1 ((u32)0x00002) /* External interrupt line 1 */
+#define EXTI_Line2 ((u32)0x00004) /* External interrupt line 2 */
+#define EXTI_Line3 ((u32)0x00008) /* External interrupt line 3 */
+#define EXTI_Line4 ((u32)0x00010) /* External interrupt line 4 */
+#define EXTI_Line5 ((u32)0x00020) /* External interrupt line 5 */
+#define EXTI_Line6 ((u32)0x00040) /* External interrupt line 6 */
+#define EXTI_Line7 ((u32)0x00080) /* External interrupt line 7 */
+#define EXTI_Line8 ((u32)0x00100) /* External interrupt line 8 */
+#define EXTI_Line9 ((u32)0x00200) /* External interrupt line 9 */
+#define EXTI_Line10 ((u32)0x00400) /* External interrupt line 10 */
+#define EXTI_Line11 ((u32)0x00800) /* External interrupt line 11 */
+#define EXTI_Line12 ((u32)0x01000) /* External interrupt line 12 */
+#define EXTI_Line13 ((u32)0x02000) /* External interrupt line 13 */
+#define EXTI_Line14 ((u32)0x04000) /* External interrupt line 14 */
+#define EXTI_Line15 ((u32)0x08000) /* External interrupt line 15 */
+#define EXTI_Line16 ((u32)0x10000) /* External interrupt line 16
+ Connected to the PVD Output */
+#define EXTI_Line17 ((u32)0x20000) /* External interrupt line 17
+ Connected to the RTC Alarm event */
+#define EXTI_Line18 ((u32)0x40000) /* External interrupt line 18
+ Connected to the USB Wakeup from
+ suspend event */
+
+#define IS_EXTI_LINE(LINE) ((((LINE) & (u32)0xFFF80000) == 0x00) && ((LINE) != (u16)0x00))
+
+#define IS_GET_EXTI_LINE(LINE) (((LINE) == EXTI_Line0) || ((LINE) == EXTI_Line1) || \
+ ((LINE) == EXTI_Line2) || ((LINE) == EXTI_Line3) || \
+ ((LINE) == EXTI_Line4) || ((LINE) == EXTI_Line5) || \
+ ((LINE) == EXTI_Line6) || ((LINE) == EXTI_Line7) || \
+ ((LINE) == EXTI_Line8) || ((LINE) == EXTI_Line9) || \
+ ((LINE) == EXTI_Line10) || ((LINE) == EXTI_Line11) || \
+ ((LINE) == EXTI_Line12) || ((LINE) == EXTI_Line13) || \
+ ((LINE) == EXTI_Line14) || ((LINE) == EXTI_Line15) || \
+ ((LINE) == EXTI_Line16) || ((LINE) == EXTI_Line17) || \
+ ((LINE) == EXTI_Line18))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void EXTI_DeInit(void);
+void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct);
+void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct);
+void EXTI_GenerateSWInterrupt(u32 EXTI_Line);
+FlagStatus EXTI_GetFlagStatus(u32 EXTI_Line);
+void EXTI_ClearFlag(u32 EXTI_Line);
+ITStatus EXTI_GetITStatus(u32 EXTI_Line);
+void EXTI_ClearITPendingBit(u32 EXTI_Line);
+
+#endif /* __STM32F10x_EXTI_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_flash.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_flash.h new file mode 100755 index 0000000..1b50230 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_flash.h @@ -0,0 +1,208 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_flash.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* FLASH firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_FLASH_H
+#define __STM32F10x_FLASH_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+#ifdef _FLASH_PROG
+/* FLASH Status */
+typedef enum
+{
+ FLASH_BUSY = 1,
+ FLASH_ERROR_PG,
+ FLASH_ERROR_WRP,
+ FLASH_COMPLETE,
+ FLASH_TIMEOUT
+}FLASH_Status;
+#endif
+
+/* Flash Latency -------------------------------------------------------------*/
+#define FLASH_Latency_0 ((u32)0x00000000) /* FLASH Zero Latency cycle */
+#define FLASH_Latency_1 ((u32)0x00000001) /* FLASH One Latency cycle */
+#define FLASH_Latency_2 ((u32)0x00000002) /* FLASH Two Latency cycles */
+
+#define IS_FLASH_LATENCY(LATENCY) (((LATENCY) == FLASH_Latency_0) || \
+ ((LATENCY) == FLASH_Latency_1) || \
+ ((LATENCY) == FLASH_Latency_2))
+
+/* Half Cycle Enable/Disable -------------------------------------------------*/
+#define FLASH_HalfCycleAccess_Enable ((u32)0x00000008) /* FLASH Half Cycle Enable */
+#define FLASH_HalfCycleAccess_Disable ((u32)0x00000000) /* FLASH Half Cycle Disable */
+
+#define IS_FLASH_HALFCYCLEACCESS_STATE(STATE) (((STATE) == FLASH_HalfCycleAccess_Enable) || \
+ ((STATE) == FLASH_HalfCycleAccess_Disable))
+
+
+/* Prefetch Buffer Enable/Disable --------------------------------------------*/
+#define FLASH_PrefetchBuffer_Enable ((u32)0x00000010) /* FLASH Prefetch Buffer Enable */
+#define FLASH_PrefetchBuffer_Disable ((u32)0x00000000) /* FLASH Prefetch Buffer Disable */
+
+#define IS_FLASH_PREFETCHBUFFER_STATE(STATE) (((STATE) == FLASH_PrefetchBuffer_Enable) || \
+ ((STATE) == FLASH_PrefetchBuffer_Disable))
+
+#ifdef _FLASH_PROG
+/* Option Bytes Write Protection ---------------------------------------------*/
+/* Values to be used with STM32F10Xxx Medium-density devices: FLASH memory density
+ ranges between 32 and 128 Kbytes with page size equal to 1 Kbytes */
+#define FLASH_WRProt_Pages0to3 ((u32)0x00000001) /* Write protection of page 0 to 3 */
+#define FLASH_WRProt_Pages4to7 ((u32)0x00000002) /* Write protection of page 4 to 7 */
+#define FLASH_WRProt_Pages8to11 ((u32)0x00000004) /* Write protection of page 8 to 11 */
+#define FLASH_WRProt_Pages12to15 ((u32)0x00000008) /* Write protection of page 12 to 15 */
+#define FLASH_WRProt_Pages16to19 ((u32)0x00000010) /* Write protection of page 16 to 19 */
+#define FLASH_WRProt_Pages20to23 ((u32)0x00000020) /* Write protection of page 20 to 23 */
+#define FLASH_WRProt_Pages24to27 ((u32)0x00000040) /* Write protection of page 24 to 27 */
+#define FLASH_WRProt_Pages28to31 ((u32)0x00000080) /* Write protection of page 28 to 31 */
+#define FLASH_WRProt_Pages32to35 ((u32)0x00000100) /* Write protection of page 32 to 35 */
+#define FLASH_WRProt_Pages36to39 ((u32)0x00000200) /* Write protection of page 36 to 39 */
+#define FLASH_WRProt_Pages40to43 ((u32)0x00000400) /* Write protection of page 40 to 43 */
+#define FLASH_WRProt_Pages44to47 ((u32)0x00000800) /* Write protection of page 44 to 47 */
+#define FLASH_WRProt_Pages48to51 ((u32)0x00001000) /* Write protection of page 48 to 51 */
+#define FLASH_WRProt_Pages52to55 ((u32)0x00002000) /* Write protection of page 52 to 55 */
+#define FLASH_WRProt_Pages56to59 ((u32)0x00004000) /* Write protection of page 56 to 59 */
+#define FLASH_WRProt_Pages60to63 ((u32)0x00008000) /* Write protection of page 60 to 63 */
+#define FLASH_WRProt_Pages64to67 ((u32)0x00010000) /* Write protection of page 64 to 67 */
+#define FLASH_WRProt_Pages68to71 ((u32)0x00020000) /* Write protection of page 68 to 71 */
+#define FLASH_WRProt_Pages72to75 ((u32)0x00040000) /* Write protection of page 72 to 75 */
+#define FLASH_WRProt_Pages76to79 ((u32)0x00080000) /* Write protection of page 76 to 79 */
+#define FLASH_WRProt_Pages80to83 ((u32)0x00100000) /* Write protection of page 80 to 83 */
+#define FLASH_WRProt_Pages84to87 ((u32)0x00200000) /* Write protection of page 84 to 87 */
+#define FLASH_WRProt_Pages88to91 ((u32)0x00400000) /* Write protection of page 88 to 91 */
+#define FLASH_WRProt_Pages92to95 ((u32)0x00800000) /* Write protection of page 92 to 95 */
+#define FLASH_WRProt_Pages96to99 ((u32)0x01000000) /* Write protection of page 96 to 99 */
+#define FLASH_WRProt_Pages100to103 ((u32)0x02000000) /* Write protection of page 100 to 103 */
+#define FLASH_WRProt_Pages104to107 ((u32)0x04000000) /* Write protection of page 104 to 107 */
+#define FLASH_WRProt_Pages108to111 ((u32)0x08000000) /* Write protection of page 108 to 111 */
+#define FLASH_WRProt_Pages112to115 ((u32)0x10000000) /* Write protection of page 112 to 115 */
+#define FLASH_WRProt_Pages116to119 ((u32)0x20000000) /* Write protection of page 115 to 119 */
+#define FLASH_WRProt_Pages120to123 ((u32)0x40000000) /* Write protection of page 120 to 123 */
+#define FLASH_WRProt_Pages124to127 ((u32)0x80000000) /* Write protection of page 124 to 127 */
+/* Values to be used with STM32F10Xxx High-density devices: FLASH memory density
+ ranges between 256 and 512 Kbytes with page size equal to 2 Kbytes */
+#define FLASH_WRProt_Pages0to1 ((u32)0x00000001) /* Write protection of page 0 to 1 */
+#define FLASH_WRProt_Pages2to3 ((u32)0x00000002) /* Write protection of page 2 to 3 */
+#define FLASH_WRProt_Pages4to5 ((u32)0x00000004) /* Write protection of page 4 to 5 */
+#define FLASH_WRProt_Pages6to7 ((u32)0x00000008) /* Write protection of page 6 to 7 */
+#define FLASH_WRProt_Pages8to9 ((u32)0x00000010) /* Write protection of page 8 to 9 */
+#define FLASH_WRProt_Pages10to11 ((u32)0x00000020) /* Write protection of page 10 to 11 */
+#define FLASH_WRProt_Pages12to13 ((u32)0x00000040) /* Write protection of page 12 to 13 */
+#define FLASH_WRProt_Pages14to15 ((u32)0x00000080) /* Write protection of page 14 to 15 */
+#define FLASH_WRProt_Pages16to17 ((u32)0x00000100) /* Write protection of page 16 to 17 */
+#define FLASH_WRProt_Pages18to19 ((u32)0x00000200) /* Write protection of page 18 to 19 */
+#define FLASH_WRProt_Pages20to21 ((u32)0x00000400) /* Write protection of page 20 to 21 */
+#define FLASH_WRProt_Pages22to23 ((u32)0x00000800) /* Write protection of page 22 to 23 */
+#define FLASH_WRProt_Pages24to25 ((u32)0x00001000) /* Write protection of page 24 to 25 */
+#define FLASH_WRProt_Pages26to27 ((u32)0x00002000) /* Write protection of page 26 to 27 */
+#define FLASH_WRProt_Pages28to29 ((u32)0x00004000) /* Write protection of page 28 to 29 */
+#define FLASH_WRProt_Pages30to31 ((u32)0x00008000) /* Write protection of page 30 to 31 */
+#define FLASH_WRProt_Pages32to33 ((u32)0x00010000) /* Write protection of page 32 to 33 */
+#define FLASH_WRProt_Pages34to35 ((u32)0x00020000) /* Write protection of page 34 to 35 */
+#define FLASH_WRProt_Pages36to37 ((u32)0x00040000) /* Write protection of page 36 to 37 */
+#define FLASH_WRProt_Pages38to39 ((u32)0x00080000) /* Write protection of page 38 to 39 */
+#define FLASH_WRProt_Pages40to41 ((u32)0x00100000) /* Write protection of page 40 to 41 */
+#define FLASH_WRProt_Pages42to43 ((u32)0x00200000) /* Write protection of page 42 to 43 */
+#define FLASH_WRProt_Pages44to45 ((u32)0x00400000) /* Write protection of page 44 to 45 */
+#define FLASH_WRProt_Pages46to47 ((u32)0x00800000) /* Write protection of page 46 to 47 */
+#define FLASH_WRProt_Pages48to49 ((u32)0x01000000) /* Write protection of page 48 to 49 */
+#define FLASH_WRProt_Pages50to51 ((u32)0x02000000) /* Write protection of page 50 to 51 */
+#define FLASH_WRProt_Pages52to53 ((u32)0x04000000) /* Write protection of page 52 to 53 */
+#define FLASH_WRProt_Pages54to55 ((u32)0x08000000) /* Write protection of page 54 to 55 */
+#define FLASH_WRProt_Pages56to57 ((u32)0x10000000) /* Write protection of page 56 to 57 */
+#define FLASH_WRProt_Pages58to59 ((u32)0x20000000) /* Write protection of page 58 to 59 */
+#define FLASH_WRProt_Pages60to61 ((u32)0x40000000) /* Write protection of page 60 to 61 */
+#define FLASH_WRProt_Pages62to255 ((u32)0x80000000) /* Write protection of page 62 to 255 */
+#define FLASH_WRProt_AllPages ((u32)0xFFFFFFFF) /* Write protection of all Pages */
+
+#define IS_FLASH_WRPROT_PAGE(PAGE) (((PAGE) != 0x00000000))
+
+#define IS_FLASH_ADDRESS(ADDRESS) (((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x0807FFFF))
+#define IS_OB_DATA_ADDRESS(ADDRESS) (((ADDRESS) == 0x1FFFF804) || ((ADDRESS) == 0x1FFFF806))
+
+/* Option Bytes IWatchdog ----------------------------------------------------*/
+#define OB_IWDG_SW ((u16)0x0001) /* Software IWDG selected */
+#define OB_IWDG_HW ((u16)0x0000) /* Hardware IWDG selected */
+
+#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW))
+
+/* Option Bytes nRST_STOP ----------------------------------------------------*/
+#define OB_STOP_NoRST ((u16)0x0002) /* No reset generated when entering in STOP */
+#define OB_STOP_RST ((u16)0x0000) /* Reset generated when entering in STOP */
+
+#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NoRST) || ((SOURCE) == OB_STOP_RST))
+
+/* Option Bytes nRST_STDBY ---------------------------------------------------*/
+#define OB_STDBY_NoRST ((u16)0x0004) /* No reset generated when entering in STANDBY */
+#define OB_STDBY_RST ((u16)0x0000) /* Reset generated when entering in STANDBY */
+
+#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NoRST) || ((SOURCE) == OB_STDBY_RST))
+
+/* FLASH Interrupts ----------------------------------------------------------*/
+#define FLASH_IT_ERROR ((u32)0x00000400) /* FPEC error interrupt source */
+#define FLASH_IT_EOP ((u32)0x00001000) /* End of FLASH Operation Interrupt source */
+
+#define IS_FLASH_IT(IT) ((((IT) & (u32)0xFFFFEBFF) == 0x00000000) && (((IT) != 0x00000000)))
+
+/* FLASH Flags ---------------------------------------------------------------*/
+#define FLASH_FLAG_BSY ((u32)0x00000001) /* FLASH Busy flag */
+#define FLASH_FLAG_EOP ((u32)0x00000020) /* FLASH End of Operation flag */
+#define FLASH_FLAG_PGERR ((u32)0x00000004) /* FLASH Program error flag */
+#define FLASH_FLAG_WRPRTERR ((u32)0x00000010) /* FLASH Write protected error flag */
+#define FLASH_FLAG_OPTERR ((u32)0x00000001) /* FLASH Option Byte error flag */
+
+#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (u32)0xFFFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000))
+
+#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \
+ ((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \
+ ((FLAG) == FLASH_FLAG_OPTERR))
+#endif
+
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void FLASH_SetLatency(u32 FLASH_Latency);
+void FLASH_HalfCycleAccessCmd(u32 FLASH_HalfCycleAccess);
+void FLASH_PrefetchBufferCmd(u32 FLASH_PrefetchBuffer);
+
+#ifdef _FLASH_PROG
+void FLASH_Unlock(void);
+void FLASH_Lock(void);
+FLASH_Status FLASH_ErasePage(u32 Page_Address);
+FLASH_Status FLASH_EraseAllPages(void);
+FLASH_Status FLASH_EraseOptionBytes(void);
+FLASH_Status FLASH_ProgramWord(u32 Address, u32 Data);
+FLASH_Status FLASH_ProgramHalfWord(u32 Address, u16 Data);
+FLASH_Status FLASH_ProgramOptionByteData(u32 Address, u8 Data);
+FLASH_Status FLASH_EnableWriteProtection(u32 FLASH_Pages);
+FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState);
+FLASH_Status FLASH_UserOptionByteConfig(u16 OB_IWDG, u16 OB_STOP, u16 OB_STDBY);
+u32 FLASH_GetUserOptionByte(void);
+u32 FLASH_GetWriteProtectionOptionByte(void);
+FlagStatus FLASH_GetReadOutProtectionStatus(void);
+FlagStatus FLASH_GetPrefetchBufferStatus(void);
+void FLASH_ITConfig(u16 FLASH_IT, FunctionalState NewState);
+FlagStatus FLASH_GetFlagStatus(u16 FLASH_FLAG);
+void FLASH_ClearFlag(u16 FLASH_FLAG);
+FLASH_Status FLASH_GetStatus(void);
+FLASH_Status FLASH_WaitForLastOperation(u32 Timeout);
+#endif
+
+#endif /* __STM32F10x_FLASH_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_fsmc.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_fsmc.h new file mode 100755 index 0000000..c338c8e --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_fsmc.h @@ -0,0 +1,355 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_fsmc.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* FSMC firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_FSMC_H
+#define __STM32F10x_FSMC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Timing parameters For NOR/SRAM Banks */
+typedef struct
+{
+ u32 FSMC_AddressSetupTime;
+ u32 FSMC_AddressHoldTime;
+ u32 FSMC_DataSetupTime;
+ u32 FSMC_BusTurnAroundDuration;
+ u32 FSMC_CLKDivision;
+ u32 FSMC_DataLatency;
+ u32 FSMC_AccessMode;
+}FSMC_NORSRAMTimingInitTypeDef;
+
+/* FSMC NOR/SRAM Init structure definition */
+typedef struct
+{
+ u32 FSMC_Bank;
+ u32 FSMC_DataAddressMux;
+ u32 FSMC_MemoryType;
+ u32 FSMC_MemoryDataWidth;
+ u32 FSMC_BurstAccessMode;
+ u32 FSMC_WaitSignalPolarity;
+ u32 FSMC_WrapMode;
+ u32 FSMC_WaitSignalActive;
+ u32 FSMC_WriteOperation;
+ u32 FSMC_WaitSignal;
+ u32 FSMC_ExtendedMode;
+ u32 FSMC_AsyncWait;
+ u32 FSMC_WriteBurst;
+ /* Timing Parameters for write and read access if the ExtendedMode is not used*/
+ FSMC_NORSRAMTimingInitTypeDef* FSMC_ReadWriteTimingStruct;
+ /* Timing Parameters for write access if the ExtendedMode is used*/
+ FSMC_NORSRAMTimingInitTypeDef* FSMC_WriteTimingStruct;
+}FSMC_NORSRAMInitTypeDef;
+
+/* Timing parameters For FSMC NAND and PCCARD Banks */
+typedef struct
+{
+ u32 FSMC_SetupTime;
+ u32 FSMC_WaitSetupTime;
+ u32 FSMC_HoldSetupTime;
+ u32 FSMC_HiZSetupTime;
+}FSMC_NAND_PCCARDTimingInitTypeDef;
+
+/* FSMC NAND Init structure definition */
+typedef struct
+{
+ u32 FSMC_Bank;
+ u32 FSMC_Waitfeature;
+ u32 FSMC_MemoryDataWidth;
+ u32 FSMC_ECC;
+ u32 FSMC_ECCPageSize;
+ u32 FSMC_AddressLowMapping;
+ u32 FSMC_TCLRSetupTime;
+ u32 FSMC_TARSetupTime;
+ /* FSMC Common Space Timing */
+ FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct;
+ /* FSMC Attribute Space Timing */
+ FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct;
+}FSMC_NANDInitTypeDef;
+
+/* FSMC PCCARD Init structure definition */
+typedef struct
+{
+ u32 FSMC_Waitfeature;
+ u32 FSMC_AddressLowMapping;
+ u32 FSMC_TCLRSetupTime;
+ u32 FSMC_TARSetupTime;
+ /* FSMC Common Space Timing */
+ FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct;
+ /* FSMC Attribute Space Timing */
+ FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct;
+ /* FSMC IO Space Timing */
+ FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_IOSpaceTimingStruct;
+}FSMC_PCCARDInitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+/*-------------------------------FSMC Banks definitions ----------------------*/
+#define FSMC_Bank1_NORSRAM1 ((u32)0x00000000)
+#define FSMC_Bank1_NORSRAM2 ((u32)0x00000002)
+#define FSMC_Bank1_NORSRAM3 ((u32)0x00000004)
+#define FSMC_Bank1_NORSRAM4 ((u32)0x00000006)
+#define FSMC_Bank2_NAND ((u32)0x00000010)
+#define FSMC_Bank3_NAND ((u32)0x00000100)
+#define FSMC_Bank4_PCCARD ((u32)0x00001000)
+
+#define IS_FSMC_NORSRAM_BANK(BANK) (((BANK) == FSMC_Bank1_NORSRAM1) || \
+ ((BANK) == FSMC_Bank1_NORSRAM2) || \
+ ((BANK) == FSMC_Bank1_NORSRAM3) || \
+ ((BANK) == FSMC_Bank1_NORSRAM4))
+
+
+#define IS_FSMC_NAND_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
+ ((BANK) == FSMC_Bank3_NAND))
+
+#define IS_FSMC_GETFLAG_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
+ ((BANK) == FSMC_Bank3_NAND) || \
+ ((BANK) == FSMC_Bank4_PCCARD))
+
+#define IS_FSMC_IT_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
+ ((BANK) == FSMC_Bank3_NAND) || \
+ ((BANK) == FSMC_Bank4_PCCARD))
+
+
+/*------------------------------- NOR/SRAM Banks -----------------------------*/
+/* FSMC Data/Address Bus Multiplexing ----------------------------------------*/
+#define FSMC_DataAddressMux_Disable ((u32)0x00000000)
+#define FSMC_DataAddressMux_Enable ((u32)0x00000002)
+
+#define IS_FSMC_MUX(MUX) (((MUX) == FSMC_DataAddressMux_Disable) || \
+ ((MUX) == FSMC_DataAddressMux_Enable))
+
+/* FSMC Memory Type ----------------------------------------------------------*/
+#define FSMC_MemoryType_SRAM ((u32)0x00000000)
+#define FSMC_MemoryType_CRAM ((u32)0x00000004)
+#define FSMC_MemoryType_NOR ((u32)0x00000008)
+#define FSMC_MemoryType_COSMORAM ((u32)0x0000000C)
+
+#define IS_FSMC_MEMORY(MEMORY) (((MEMORY) == FSMC_MemoryType_SRAM) || \
+ ((MEMORY) == FSMC_MemoryType_CRAM)|| \
+ ((MEMORY) == FSMC_MemoryType_NOR)|| \
+ ((MEMORY) == FSMC_MemoryType_COSMORAM))
+
+/* FSMC Data Width ----------------------------------------------------------*/
+#define FSMC_MemoryDataWidth_8b ((u32)0x00000000)
+#define FSMC_MemoryDataWidth_16b ((u32)0x00000010)
+
+#define IS_FSMC_MEMORY_WIDTH(WIDTH) (((WIDTH) == FSMC_MemoryDataWidth_8b) || \
+ ((WIDTH) == FSMC_MemoryDataWidth_16b))
+
+
+/* FSMC Burst Access Mode ----------------------------------------------------*/
+#define FSMC_BurstAccessMode_Disable ((u32)0x00000000)
+#define FSMC_BurstAccessMode_Enable ((u32)0x00000100)
+
+#define IS_FSMC_BURSTMODE(STATE) (((STATE) == FSMC_BurstAccessMode_Disable) || \
+ ((STATE) == FSMC_BurstAccessMode_Enable))
+
+/* FSMC Wait Signal Polarity -------------------------------------------------*/
+#define FSMC_WaitSignalPolarity_Low ((u32)0x00000000)
+#define FSMC_WaitSignalPolarity_High ((u32)0x00000200)
+
+#define IS_FSMC_WAIT_POLARITY(POLARITY) (((POLARITY) == FSMC_WaitSignalPolarity_Low) || \
+ ((POLARITY) == FSMC_WaitSignalPolarity_High))
+
+/* FSMC Wrap Mode ------------------------------------------------------------*/
+#define FSMC_WrapMode_Disable ((u32)0x00000000)
+#define FSMC_WrapMode_Enable ((u32)0x00000400)
+
+#define IS_FSMC_WRAP_MODE(MODE) (((MODE) == FSMC_WrapMode_Disable) || \
+ ((MODE) == FSMC_WrapMode_Enable))
+
+/* FSMC Wait Timing ----------------------------------------------------------*/
+#define FSMC_WaitSignalActive_BeforeWaitState ((u32)0x00000000)
+#define FSMC_WaitSignalActive_DuringWaitState ((u32)0x00000800)
+
+#define IS_FSMC_WAIT_SIGNAL_ACTIVE(ACTIVE) (((ACTIVE) == FSMC_WaitSignalActive_BeforeWaitState) || \
+ ((ACTIVE) == FSMC_WaitSignalActive_DuringWaitState))
+
+/* FSMC Write Operation ------------------------------------------------------*/
+#define FSMC_WriteOperation_Disable ((u32)0x00000000)
+#define FSMC_WriteOperation_Enable ((u32)0x00001000)
+
+#define IS_FSMC_WRITE_OPERATION(OPERATION) (((OPERATION) == FSMC_WriteOperation_Disable) || \
+ ((OPERATION) == FSMC_WriteOperation_Enable))
+
+/* FSMC Wait Signal ----------------------------------------------------------*/
+#define FSMC_WaitSignal_Disable ((u32)0x00000000)
+#define FSMC_WaitSignal_Enable ((u32)0x00002000)
+
+#define IS_FSMC_WAITE_SIGNAL(SIGNAL) (((SIGNAL) == FSMC_WaitSignal_Disable) || \
+ ((SIGNAL) == FSMC_WaitSignal_Enable))
+
+/* FSMC Extended Mode --------------------------------------------------------*/
+#define FSMC_ExtendedMode_Disable ((u32)0x00000000)
+#define FSMC_ExtendedMode_Enable ((u32)0x00004000)
+
+#define IS_FSMC_EXTENDED_MODE(MODE) (((MODE) == FSMC_ExtendedMode_Disable) || \
+ ((MODE) == FSMC_ExtendedMode_Enable))
+
+/* FSMC Asynchronous Wait ----------------------------------------------------*/
+#define FSMC_AsyncWait_Disable ((u32)0x00000000)
+#define FSMC_AsyncWait_Enable ((u32)0x00008000)
+
+#define IS_FSMC_ASYNC_WAIT(WAIT) (((WAIT) == FSMC_AsyncWait_Disable) || \
+ ((WAIT) == FSMC_AsyncWait_Enable))
+
+/* FSMC Write Burst ----------------------------------------------------------*/
+#define FSMC_WriteBurst_Disable ((u32)0x00000000)
+#define FSMC_WriteBurst_Enable ((u32)0x00080000)
+
+#define IS_FSMC_WRITE_BURST(BURST) (((BURST) == FSMC_WriteBurst_Disable) || \
+ ((BURST) == FSMC_WriteBurst_Enable))
+
+/* FSMC Address Setup Time ---------------------------------------------------*/
+#define IS_FSMC_ADDRESS_SETUP_TIME(TIME) ((TIME) <= 0xF)
+
+/* FSMC Address Hold Time ----------------------------------------------------*/
+#define IS_FSMC_ADDRESS_HOLD_TIME(TIME) ((TIME) <= 0xF)
+
+/* FSMC Data Setup Time ------------------------------------------------------*/
+#define IS_FSMC_DATASETUP_TIME(TIME) (((TIME) > 0) && ((TIME) <= 0xFF))
+
+/* FSMC Bus Turn around Duration ---------------------------------------------*/
+#define IS_FSMC_TURNAROUND_TIME(TIME) ((TIME) <= 0xF)
+
+/* FSMC CLK Division ---------------------------------------------------------*/
+#define IS_FSMC_CLK_DIV(DIV) ((DIV) <= 0xF)
+
+/* FSMC Data Latency ---------------------------------------------------------*/
+#define IS_FSMC_DATA_LATENCY(LATENCY) ((LATENCY) <= 0xF)
+
+/* FSMC Access Mode ----------------------------------------------------------*/
+#define FSMC_AccessMode_A ((u32)0x00000000)
+#define FSMC_AccessMode_B ((u32)0x10000000)
+#define FSMC_AccessMode_C ((u32)0x20000000)
+#define FSMC_AccessMode_D ((u32)0x30000000)
+
+#define IS_FSMC_ACCESS_MODE(MODE) (((MODE) == FSMC_AccessMode_A) || \
+ ((MODE) == FSMC_AccessMode_B) || \
+ ((MODE) == FSMC_AccessMode_C) || \
+ ((MODE) == FSMC_AccessMode_D))
+
+/*----------------------------- NAND and PCCARD Banks ------------------------*/
+/* FSMC Wait feature ---------------------------------------------------------*/
+#define FSMC_Waitfeature_Disable ((u32)0x00000000)
+#define FSMC_Waitfeature_Enable ((u32)0x00000002)
+
+#define IS_FSMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FSMC_Waitfeature_Disable) || \
+ ((FEATURE) == FSMC_Waitfeature_Enable))
+
+/* FSMC Memory Data Width ----------------------------------------------------*/
+#define FSMC_MemoryDataWidth_8b ((u32)0x00000000)
+#define FSMC_MemoryDataWidth_16b ((u32)0x00000010)
+
+#define IS_FSMC_DATA_WIDTH(WIDTH) (((WIDTH) == FSMC_MemoryDataWidth_8b) || \
+ ((WIDTH) == FSMC_MemoryDataWidth_16b))
+
+/* FSMC ECC ------------------------------------------------------------------*/
+#define FSMC_ECC_Disable ((u32)0x00000000)
+#define FSMC_ECC_Enable ((u32)0x00000040)
+
+#define IS_FSMC_ECC_STATE(STATE) (((STATE) == FSMC_ECC_Disable) || \
+ ((STATE) == FSMC_ECC_Enable))
+
+/* FSMC ECC Page Size --------------------------------------------------------*/
+#define FSMC_ECCPageSize_256Bytes ((u32)0x00000000)
+#define FSMC_ECCPageSize_512Bytes ((u32)0x00020000)
+#define FSMC_ECCPageSize_1024Bytes ((u32)0x00040000)
+#define FSMC_ECCPageSize_2048Bytes ((u32)0x00060000)
+#define FSMC_ECCPageSize_4096Bytes ((u32)0x00080000)
+#define FSMC_ECCPageSize_8192Bytes ((u32)0x000A0000)
+
+#define IS_FSMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FSMC_ECCPageSize_256Bytes) || \
+ ((SIZE) == FSMC_ECCPageSize_512Bytes) || \
+ ((SIZE) == FSMC_ECCPageSize_1024Bytes) || \
+ ((SIZE) == FSMC_ECCPageSize_2048Bytes) || \
+ ((SIZE) == FSMC_ECCPageSize_4096Bytes) || \
+ ((SIZE) == FSMC_ECCPageSize_8192Bytes))
+
+/* FSMC Address Low Mapping --------------------------------------------------*/
+#define FSMC_AddressLowMapping_Direct ((u32)0x00000000)
+#define FSMC_AddressLowMapping_InDirect ((u32)0x00000100)
+
+#define IS_FSMC_ADDRESS_LOW_MAPPING(MAPPING) (((MAPPING) == FSMC_AddressLowMapping_Direct) || \
+ ((MAPPING) == FSMC_AddressLowMapping_InDirect))
+/* FSMC TCLR Setup Time ------------------------------------------------------*/
+#define IS_FSMC_TCLR_TIME(TIME) ((TIME) <= 0xFF)
+
+/* FSMC TAR Setup Time -------------------------------------------------------*/
+#define IS_FSMC_TAR_TIME(TIME) ((TIME) <= 0xFF)
+
+/* FSMC Setup Time ----------------------------------------------------*/
+#define IS_FSMC_SETUP_TIME(TIME) ((TIME) <= 0xFF)
+
+/* FSMC Wait Setup Time -----------------------------------------------*/
+#define IS_FSMC_WAIT_TIME(TIME) ((TIME) <= 0xFF)
+
+/* FSMC Hold Setup Time -----------------------------------------------*/
+#define IS_FSMC_HOLD_TIME(TIME) ((TIME) <= 0xFF)
+
+/* FSMC HiZ Setup Time ------------------------------------------------*/
+#define IS_FSMC_HIZ_TIME(TIME) ((TIME) <= 0xFF)
+
+/* FSMC Interrupt sources ----------------------------------------------------*/
+#define FSMC_IT_RisingEdge ((u32)0x00000008)
+#define FSMC_IT_Level ((u32)0x00000010)
+#define FSMC_IT_FallingEdge ((u32)0x00000020)
+
+#define IS_FSMC_IT(IT) ((((IT) & (u32)0xFFFFFFC7) == 0x00000000) && ((IT) != 0x00000000))
+
+#define IS_FSMC_GET_IT(IT) (((IT) == FSMC_IT_RisingEdge) || \
+ ((IT) == FSMC_IT_Level) || \
+ ((IT) == FSMC_IT_FallingEdge))
+
+/* FSMC Flags ----------------------------------------------------------------*/
+#define FSMC_FLAG_RisingEdge ((u32)0x00000001)
+#define FSMC_FLAG_Level ((u32)0x00000002)
+#define FSMC_FLAG_FallingEdge ((u32)0x00000004)
+#define FSMC_FLAG_FEMPT ((u32)0x00000040)
+
+#define IS_FSMC_GET_FLAG(FLAG) (((FLAG) == FSMC_FLAG_RisingEdge) || \
+ ((FLAG) == FSMC_FLAG_Level) || \
+ ((FLAG) == FSMC_FLAG_FallingEdge) || \
+ ((FLAG) == FSMC_FLAG_FEMPT))
+
+#define IS_FSMC_CLEAR_FLAG(FLAG) ((((FLAG) & (u32)0xFFFFFFF8) == 0x00000000) && ((FLAG) != 0x00000000))
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void FSMC_NORSRAMDeInit(u32 FSMC_Bank);
+void FSMC_NANDDeInit(u32 FSMC_Bank);
+void FSMC_PCCARDDeInit(void);
+void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct);
+void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct);
+void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct);
+void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct);
+void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct);
+void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct);
+void FSMC_NORSRAMCmd(u32 FSMC_Bank, FunctionalState NewState);
+void FSMC_NANDCmd(u32 FSMC_Bank, FunctionalState NewState);
+void FSMC_PCCARDCmd(FunctionalState NewState);
+void FSMC_NANDECCCmd(u32 FSMC_Bank, FunctionalState NewState);
+u32 FSMC_GetECC(u32 FSMC_Bank);
+void FSMC_ITConfig(u32 FSMC_Bank, u32 FSMC_IT, FunctionalState NewState);
+FlagStatus FSMC_GetFlagStatus(u32 FSMC_Bank, u32 FSMC_FLAG);
+void FSMC_ClearFlag(u32 FSMC_Bank, u32 FSMC_FLAG);
+ITStatus FSMC_GetITStatus(u32 FSMC_Bank, u32 FSMC_IT);
+void FSMC_ClearITPendingBit(u32 FSMC_Bank, u32 FSMC_IT);
+
+#endif /*__STM32F10x_FSMC_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_gpio.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_gpio.h new file mode 100755 index 0000000..151cdde --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_gpio.h @@ -0,0 +1,237 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_gpio.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* GPIO firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_GPIO_H
+#define __STM32F10x_GPIO_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+#define IS_GPIO_ALL_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == GPIOA_BASE) || \
+ ((*(u32*)&(PERIPH)) == GPIOB_BASE) || \
+ ((*(u32*)&(PERIPH)) == GPIOC_BASE) || \
+ ((*(u32*)&(PERIPH)) == GPIOD_BASE) || \
+ ((*(u32*)&(PERIPH)) == GPIOE_BASE) || \
+ ((*(u32*)&(PERIPH)) == GPIOF_BASE) || \
+ ((*(u32*)&(PERIPH)) == GPIOG_BASE))
+
+/* Output Maximum frequency selection ----------------------------------------*/
+typedef enum
+{
+ GPIO_Speed_10MHz = 1,
+ GPIO_Speed_2MHz,
+ GPIO_Speed_50MHz
+}GPIOSpeed_TypeDef;
+
+#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_Speed_10MHz) || ((SPEED) == GPIO_Speed_2MHz) || \
+ ((SPEED) == GPIO_Speed_50MHz))
+
+/* Configuration Mode enumeration --------------------------------------------*/
+typedef enum
+{ GPIO_Mode_AIN = 0x0,
+ GPIO_Mode_IN_FLOATING = 0x04,
+ GPIO_Mode_IPD = 0x28,
+ GPIO_Mode_IPU = 0x48,
+ GPIO_Mode_Out_OD = 0x14,
+ GPIO_Mode_Out_PP = 0x10,
+ GPIO_Mode_AF_OD = 0x1C,
+ GPIO_Mode_AF_PP = 0x18
+}GPIOMode_TypeDef;
+
+#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_Mode_AIN) || ((MODE) == GPIO_Mode_IN_FLOATING) || \
+ ((MODE) == GPIO_Mode_IPD) || ((MODE) == GPIO_Mode_IPU) || \
+ ((MODE) == GPIO_Mode_Out_OD) || ((MODE) == GPIO_Mode_Out_PP) || \
+ ((MODE) == GPIO_Mode_AF_OD) || ((MODE) == GPIO_Mode_AF_PP))
+
+/* GPIO Init structure definition */
+typedef struct
+{
+ u16 GPIO_Pin;
+ GPIOSpeed_TypeDef GPIO_Speed;
+ GPIOMode_TypeDef GPIO_Mode;
+}GPIO_InitTypeDef;
+
+/* Bit_SET and Bit_RESET enumeration -----------------------------------------*/
+typedef enum
+{ Bit_RESET = 0,
+ Bit_SET
+}BitAction;
+#define IS_GPIO_BIT_ACTION(ACTION) (((ACTION) == Bit_RESET) || ((ACTION) == Bit_SET))
+
+/* Exported constants --------------------------------------------------------*/
+/* GPIO pins define ----------------------------------------------------------*/
+#define GPIO_Pin_0 ((u16)0x0001) /* Pin 0 selected */
+#define GPIO_Pin_1 ((u16)0x0002) /* Pin 1 selected */
+#define GPIO_Pin_2 ((u16)0x0004) /* Pin 2 selected */
+#define GPIO_Pin_3 ((u16)0x0008) /* Pin 3 selected */
+#define GPIO_Pin_4 ((u16)0x0010) /* Pin 4 selected */
+#define GPIO_Pin_5 ((u16)0x0020) /* Pin 5 selected */
+#define GPIO_Pin_6 ((u16)0x0040) /* Pin 6 selected */
+#define GPIO_Pin_7 ((u16)0x0080) /* Pin 7 selected */
+#define GPIO_Pin_8 ((u16)0x0100) /* Pin 8 selected */
+#define GPIO_Pin_9 ((u16)0x0200) /* Pin 9 selected */
+#define GPIO_Pin_10 ((u16)0x0400) /* Pin 10 selected */
+#define GPIO_Pin_11 ((u16)0x0800) /* Pin 11 selected */
+#define GPIO_Pin_12 ((u16)0x1000) /* Pin 12 selected */
+#define GPIO_Pin_13 ((u16)0x2000) /* Pin 13 selected */
+#define GPIO_Pin_14 ((u16)0x4000) /* Pin 14 selected */
+#define GPIO_Pin_15 ((u16)0x8000) /* Pin 15 selected */
+#define GPIO_Pin_All ((u16)0xFFFF) /* All pins selected */
+
+#define IS_GPIO_PIN(PIN) ((((PIN) & (u16)0x00) == 0x00) && ((PIN) != (u16)0x00))
+
+#define IS_GET_GPIO_PIN(PIN) (((PIN) == GPIO_Pin_0) || \
+ ((PIN) == GPIO_Pin_1) || \
+ ((PIN) == GPIO_Pin_2) || \
+ ((PIN) == GPIO_Pin_3) || \
+ ((PIN) == GPIO_Pin_4) || \
+ ((PIN) == GPIO_Pin_5) || \
+ ((PIN) == GPIO_Pin_6) || \
+ ((PIN) == GPIO_Pin_7) || \
+ ((PIN) == GPIO_Pin_8) || \
+ ((PIN) == GPIO_Pin_9) || \
+ ((PIN) == GPIO_Pin_10) || \
+ ((PIN) == GPIO_Pin_11) || \
+ ((PIN) == GPIO_Pin_12) || \
+ ((PIN) == GPIO_Pin_13) || \
+ ((PIN) == GPIO_Pin_14) || \
+ ((PIN) == GPIO_Pin_15))
+
+/* GPIO Remap define ---------------------------------------------------------*/
+#define GPIO_Remap_SPI1 ((u32)0x00000001) /* SPI1 Alternate Function mapping */
+#define GPIO_Remap_I2C1 ((u32)0x00000002) /* I2C1 Alternate Function mapping */
+#define GPIO_Remap_USART1 ((u32)0x00000004) /* USART1 Alternate Function mapping */
+#define GPIO_Remap_USART2 ((u32)0x00000008) /* USART2 Alternate Function mapping */
+#define GPIO_PartialRemap_USART3 ((u32)0x00140010) /* USART3 Partial Alternate Function mapping */
+#define GPIO_FullRemap_USART3 ((u32)0x00140030) /* USART3 Full Alternate Function mapping */
+#define GPIO_PartialRemap_TIM1 ((u32)0x00160040) /* TIM1 Partial Alternate Function mapping */
+#define GPIO_FullRemap_TIM1 ((u32)0x001600C0) /* TIM1 Full Alternate Function mapping */
+#define GPIO_PartialRemap1_TIM2 ((u32)0x00180100) /* TIM2 Partial1 Alternate Function mapping */
+#define GPIO_PartialRemap2_TIM2 ((u32)0x00180200) /* TIM2 Partial2 Alternate Function mapping */
+#define GPIO_FullRemap_TIM2 ((u32)0x00180300) /* TIM2 Full Alternate Function mapping */
+#define GPIO_PartialRemap_TIM3 ((u32)0x001A0800) /* TIM3 Partial Alternate Function mapping */
+#define GPIO_FullRemap_TIM3 ((u32)0x001A0C00) /* TIM3 Full Alternate Function mapping */
+#define GPIO_Remap_TIM4 ((u32)0x00001000) /* TIM4 Alternate Function mapping */
+#define GPIO_Remap1_CAN ((u32)0x001D4000) /* CAN Alternate Function mapping */
+#define GPIO_Remap2_CAN ((u32)0x001D6000) /* CAN Alternate Function mapping */
+#define GPIO_Remap_PD01 ((u32)0x00008000) /* PD01 Alternate Function mapping */
+#define GPIO_Remap_TIM5CH4_LSI ((u32)0x00200001) /* LSI connected to TIM5 Channel4 input capture for calibration */
+#define GPIO_Remap_ADC1_ETRGINJ ((u32)0x00200002) /* ADC1 External Trigger Injected Conversion remapping */
+#define GPIO_Remap_ADC1_ETRGREG ((u32)0x00200004) /* ADC1 External Trigger Regular Conversion remapping */
+#define GPIO_Remap_ADC2_ETRGINJ ((u32)0x00200008) /* ADC2 External Trigger Injected Conversion remapping */
+#define GPIO_Remap_ADC2_ETRGREG ((u32)0x00200010) /* ADC2 External Trigger Regular Conversion remapping */
+#define GPIO_Remap_SWJ_NoJTRST ((u32)0x00300100) /* Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST */
+#define GPIO_Remap_SWJ_JTAGDisable ((u32)0x00300200) /* JTAG-DP Disabled and SW-DP Enabled */
+#define GPIO_Remap_SWJ_Disable ((u32)0x00300400) /* Full SWJ Disabled (JTAG-DP + SW-DP) */
+
+
+#define IS_GPIO_REMAP(REMAP) (((REMAP) == GPIO_Remap_SPI1) || ((REMAP) == GPIO_Remap_I2C1) || \
+ ((REMAP) == GPIO_Remap_USART1) || ((REMAP) == GPIO_Remap_USART2) || \
+ ((REMAP) == GPIO_PartialRemap_USART3) || ((REMAP) == GPIO_FullRemap_USART3) || \
+ ((REMAP) == GPIO_PartialRemap_TIM1) || ((REMAP) == GPIO_FullRemap_TIM1) || \
+ ((REMAP) == GPIO_PartialRemap1_TIM2) || ((REMAP) == GPIO_PartialRemap2_TIM2) || \
+ ((REMAP) == GPIO_FullRemap_TIM2) || ((REMAP) == GPIO_PartialRemap_TIM3) || \
+ ((REMAP) == GPIO_FullRemap_TIM3) || ((REMAP) == GPIO_Remap_TIM4) || \
+ ((REMAP) == GPIO_Remap1_CAN) || ((REMAP) == GPIO_Remap2_CAN) || \
+ ((REMAP) == GPIO_Remap_PD01) || ((REMAP) == GPIO_Remap_TIM5CH4_LSI) || \
+ ((REMAP) == GPIO_Remap_ADC1_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC1_ETRGREG) || \
+ ((REMAP) == GPIO_Remap_ADC2_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC2_ETRGREG) || \
+ ((REMAP) == GPIO_Remap_SWJ_NoJTRST) || ((REMAP) == GPIO_Remap_SWJ_JTAGDisable)|| \
+ ((REMAP) == GPIO_Remap_SWJ_Disable))
+
+/* GPIO Port Sources ---------------------------------------------------------*/
+#define GPIO_PortSourceGPIOA ((u8)0x00)
+#define GPIO_PortSourceGPIOB ((u8)0x01)
+#define GPIO_PortSourceGPIOC ((u8)0x02)
+#define GPIO_PortSourceGPIOD ((u8)0x03)
+#define GPIO_PortSourceGPIOE ((u8)0x04)
+#define GPIO_PortSourceGPIOF ((u8)0x05)
+#define GPIO_PortSourceGPIOG ((u8)0x06)
+
+#define IS_GPIO_EVENTOUT_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOB) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOC) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOD) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOE))
+
+#define IS_GPIO_EXTI_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOB) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOC) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOD) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOE) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOF) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOG))
+
+/* GPIO Pin sources ----------------------------------------------------------*/
+#define GPIO_PinSource0 ((u8)0x00)
+#define GPIO_PinSource1 ((u8)0x01)
+#define GPIO_PinSource2 ((u8)0x02)
+#define GPIO_PinSource3 ((u8)0x03)
+#define GPIO_PinSource4 ((u8)0x04)
+#define GPIO_PinSource5 ((u8)0x05)
+#define GPIO_PinSource6 ((u8)0x06)
+#define GPIO_PinSource7 ((u8)0x07)
+#define GPIO_PinSource8 ((u8)0x08)
+#define GPIO_PinSource9 ((u8)0x09)
+#define GPIO_PinSource10 ((u8)0x0A)
+#define GPIO_PinSource11 ((u8)0x0B)
+#define GPIO_PinSource12 ((u8)0x0C)
+#define GPIO_PinSource13 ((u8)0x0D)
+#define GPIO_PinSource14 ((u8)0x0E)
+#define GPIO_PinSource15 ((u8)0x0F)
+
+#define IS_GPIO_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == GPIO_PinSource0) || \
+ ((PINSOURCE) == GPIO_PinSource1) || \
+ ((PINSOURCE) == GPIO_PinSource2) || \
+ ((PINSOURCE) == GPIO_PinSource3) || \
+ ((PINSOURCE) == GPIO_PinSource4) || \
+ ((PINSOURCE) == GPIO_PinSource5) || \
+ ((PINSOURCE) == GPIO_PinSource6) || \
+ ((PINSOURCE) == GPIO_PinSource7) || \
+ ((PINSOURCE) == GPIO_PinSource8) || \
+ ((PINSOURCE) == GPIO_PinSource9) || \
+ ((PINSOURCE) == GPIO_PinSource10) || \
+ ((PINSOURCE) == GPIO_PinSource11) || \
+ ((PINSOURCE) == GPIO_PinSource12) || \
+ ((PINSOURCE) == GPIO_PinSource13) || \
+ ((PINSOURCE) == GPIO_PinSource14) || \
+ ((PINSOURCE) == GPIO_PinSource15))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void GPIO_DeInit(GPIO_TypeDef* GPIOx);
+void GPIO_AFIODeInit(void);
+void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct);
+void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct);
+u8 GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin);
+u16 GPIO_ReadInputData(GPIO_TypeDef* GPIOx);
+u8 GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin);
+u16 GPIO_ReadOutputData(GPIO_TypeDef* GPIOx);
+void GPIO_SetBits(GPIO_TypeDef* GPIOx, u16 GPIO_Pin);
+void GPIO_ResetBits(GPIO_TypeDef* GPIOx, u16 GPIO_Pin);
+void GPIO_WriteBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin, BitAction BitVal);
+void GPIO_Write(GPIO_TypeDef* GPIOx, u16 PortVal);
+void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, u16 GPIO_Pin);
+void GPIO_EventOutputConfig(u8 GPIO_PortSource, u8 GPIO_PinSource);
+void GPIO_EventOutputCmd(FunctionalState NewState);
+void GPIO_PinRemapConfig(u32 GPIO_Remap, FunctionalState NewState);
+void GPIO_EXTILineConfig(u8 GPIO_PortSource, u8 GPIO_PinSource);
+
+#endif /* __STM32F10x_GPIO_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_i2c.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_i2c.h new file mode 100755 index 0000000..7e694cf --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_i2c.h @@ -0,0 +1,289 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_i2c.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* I2C firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_I2C_H
+#define __STM32F10x_I2C_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* I2C Init structure definition */
+typedef struct
+{
+ u16 I2C_Mode;
+ u16 I2C_DutyCycle;
+ u16 I2C_OwnAddress1;
+ u16 I2C_Ack;
+ u16 I2C_AcknowledgedAddress;
+ u32 I2C_ClockSpeed;
+}I2C_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+#define IS_I2C_ALL_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == I2C1_BASE) || \
+ ((*(u32*)&(PERIPH)) == I2C2_BASE))
+
+/* I2C modes */
+#define I2C_Mode_I2C ((u16)0x0000)
+#define I2C_Mode_SMBusDevice ((u16)0x0002)
+#define I2C_Mode_SMBusHost ((u16)0x000A)
+
+#define IS_I2C_MODE(MODE) (((MODE) == I2C_Mode_I2C) || \
+ ((MODE) == I2C_Mode_SMBusDevice) || \
+ ((MODE) == I2C_Mode_SMBusHost))
+/* I2C duty cycle in fast mode */
+#define I2C_DutyCycle_16_9 ((u16)0x4000)
+#define I2C_DutyCycle_2 ((u16)0xBFFF)
+
+#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DutyCycle_16_9) || \
+ ((CYCLE) == I2C_DutyCycle_2))
+
+/* I2C cknowledgementy */
+#define I2C_Ack_Enable ((u16)0x0400)
+#define I2C_Ack_Disable ((u16)0x0000)
+
+#define IS_I2C_ACK_STATE(STATE) (((STATE) == I2C_Ack_Enable) || \
+ ((STATE) == I2C_Ack_Disable))
+
+/* I2C transfer direction */
+#define I2C_Direction_Transmitter ((u8)0x00)
+#define I2C_Direction_Receiver ((u8)0x01)
+
+#define IS_I2C_DIRECTION(DIRECTION) (((DIRECTION) == I2C_Direction_Transmitter) || \
+ ((DIRECTION) == I2C_Direction_Receiver))
+
+/* I2C acknowledged address defines */
+#define I2C_AcknowledgedAddress_7bit ((u16)0x4000)
+#define I2C_AcknowledgedAddress_10bit ((u16)0xC000)
+
+#define IS_I2C_ACKNOWLEDGE_ADDRESS(ADDRESS) (((ADDRESS) == I2C_AcknowledgedAddress_7bit) || \
+ ((ADDRESS) == I2C_AcknowledgedAddress_10bit))
+
+/* I2C registers */
+#define I2C_Register_CR1 ((u8)0x00)
+#define I2C_Register_CR2 ((u8)0x04)
+#define I2C_Register_OAR1 ((u8)0x08)
+#define I2C_Register_OAR2 ((u8)0x0C)
+#define I2C_Register_DR ((u8)0x10)
+#define I2C_Register_SR1 ((u8)0x14)
+#define I2C_Register_SR2 ((u8)0x18)
+#define I2C_Register_CCR ((u8)0x1C)
+#define I2C_Register_TRISE ((u8)0x20)
+
+#define IS_I2C_REGISTER(REGISTER) (((REGISTER) == I2C_Register_CR1) || \
+ ((REGISTER) == I2C_Register_CR2) || \
+ ((REGISTER) == I2C_Register_OAR1) || \
+ ((REGISTER) == I2C_Register_OAR2) || \
+ ((REGISTER) == I2C_Register_DR) || \
+ ((REGISTER) == I2C_Register_SR1) || \
+ ((REGISTER) == I2C_Register_SR2) || \
+ ((REGISTER) == I2C_Register_CCR) || \
+ ((REGISTER) == I2C_Register_TRISE))
+
+/* I2C SMBus alert pin level */
+#define I2C_SMBusAlert_Low ((u16)0x2000)
+#define I2C_SMBusAlert_High ((u16)0xDFFF)
+
+#define IS_I2C_SMBUS_ALERT(ALERT) (((ALERT) == I2C_SMBusAlert_Low) || \
+ ((ALERT) == I2C_SMBusAlert_High))
+
+/* I2C PEC position */
+#define I2C_PECPosition_Next ((u16)0x0800)
+#define I2C_PECPosition_Current ((u16)0xF7FF)
+
+#define IS_I2C_PEC_POSITION(POSITION) (((POSITION) == I2C_PECPosition_Next) || \
+ ((POSITION) == I2C_PECPosition_Current))
+
+/* I2C interrupts definition */
+#define I2C_IT_BUF ((u16)0x0400)
+#define I2C_IT_EVT ((u16)0x0200)
+#define I2C_IT_ERR ((u16)0x0100)
+
+#define IS_I2C_CONFIG_IT(IT) ((((IT) & (u16)0xF8FF) == 0x00) && ((IT) != 0x00))
+
+/* I2C interrupts definition */
+#define I2C_IT_SMBALERT ((u32)0x10008000)
+#define I2C_IT_TIMEOUT ((u32)0x10004000)
+#define I2C_IT_PECERR ((u32)0x10001000)
+#define I2C_IT_OVR ((u32)0x10000800)
+#define I2C_IT_AF ((u32)0x10000400)
+#define I2C_IT_ARLO ((u32)0x10000200)
+#define I2C_IT_BERR ((u32)0x10000100)
+#define I2C_IT_TXE ((u32)0x00000080)
+#define I2C_IT_RXNE ((u32)0x00000040)
+#define I2C_IT_STOPF ((u32)0x60000010)
+#define I2C_IT_ADD10 ((u32)0x20000008)
+#define I2C_IT_BTF ((u32)0x60000004)
+#define I2C_IT_ADDR ((u32)0xA0000002)
+#define I2C_IT_SB ((u32)0x20000001)
+
+#define IS_I2C_CLEAR_IT(IT) (((IT) == I2C_IT_SMBALERT) || ((IT) == I2C_IT_TIMEOUT) || \
+ ((IT) == I2C_IT_PECERR) || ((IT) == I2C_IT_OVR) || \
+ ((IT) == I2C_IT_AF) || ((IT) == I2C_IT_ARLO) || \
+ ((IT) == I2C_IT_BERR) || ((IT) == I2C_IT_STOPF) || \
+ ((IT) == I2C_IT_ADD10) || ((IT) == I2C_IT_BTF) || \
+ ((IT) == I2C_IT_ADDR) || ((IT) == I2C_IT_SB))
+
+#define IS_I2C_GET_IT(IT) (((IT) == I2C_IT_SMBALERT) || ((IT) == I2C_IT_TIMEOUT) || \
+ ((IT) == I2C_IT_PECERR) || ((IT) == I2C_IT_OVR) || \
+ ((IT) == I2C_IT_AF) || ((IT) == I2C_IT_ARLO) || \
+ ((IT) == I2C_IT_BERR) || ((IT) == I2C_IT_TXE) || \
+ ((IT) == I2C_IT_RXNE) || ((IT) == I2C_IT_STOPF) || \
+ ((IT) == I2C_IT_ADD10) || ((IT) == I2C_IT_BTF) || \
+ ((IT) == I2C_IT_ADDR) || ((IT) == I2C_IT_SB))
+
+/* I2C flags definition */
+#define I2C_FLAG_DUALF ((u32)0x00800000)
+#define I2C_FLAG_SMBHOST ((u32)0x00400000)
+#define I2C_FLAG_SMBDEFAULT ((u32)0x00200000)
+#define I2C_FLAG_GENCALL ((u32)0x00100000)
+#define I2C_FLAG_TRA ((u32)0x00040000)
+#define I2C_FLAG_BUSY ((u32)0x00020000)
+#define I2C_FLAG_MSL ((u32)0x00010000)
+#define I2C_FLAG_SMBALERT ((u32)0x10008000)
+#define I2C_FLAG_TIMEOUT ((u32)0x10004000)
+#define I2C_FLAG_PECERR ((u32)0x10001000)
+#define I2C_FLAG_OVR ((u32)0x10000800)
+#define I2C_FLAG_AF ((u32)0x10000400)
+#define I2C_FLAG_ARLO ((u32)0x10000200)
+#define I2C_FLAG_BERR ((u32)0x10000100)
+#define I2C_FLAG_TXE ((u32)0x00000080)
+#define I2C_FLAG_RXNE ((u32)0x00000040)
+#define I2C_FLAG_STOPF ((u32)0x60000010)
+#define I2C_FLAG_ADD10 ((u32)0x20000008)
+#define I2C_FLAG_BTF ((u32)0x60000004)
+#define I2C_FLAG_ADDR ((u32)0xA0000002)
+#define I2C_FLAG_SB ((u32)0x20000001)
+
+#define IS_I2C_CLEAR_FLAG(FLAG) (((FLAG) == I2C_FLAG_SMBALERT) || ((FLAG) == I2C_FLAG_TIMEOUT) || \
+ ((FLAG) == I2C_FLAG_PECERR) || ((FLAG) == I2C_FLAG_OVR) || \
+ ((FLAG) == I2C_FLAG_AF) || ((FLAG) == I2C_FLAG_ARLO) || \
+ ((FLAG) == I2C_FLAG_BERR) || ((FLAG) == I2C_FLAG_STOPF) || \
+ ((FLAG) == I2C_FLAG_ADD10) || ((FLAG) == I2C_FLAG_BTF) || \
+ ((FLAG) == I2C_FLAG_ADDR) || ((FLAG) == I2C_FLAG_SB))
+
+#define IS_I2C_GET_FLAG(FLAG) (((FLAG) == I2C_FLAG_DUALF) || ((FLAG) == I2C_FLAG_SMBHOST) || \
+ ((FLAG) == I2C_FLAG_SMBDEFAULT) || ((FLAG) == I2C_FLAG_GENCALL) || \
+ ((FLAG) == I2C_FLAG_TRA) || ((FLAG) == I2C_FLAG_BUSY) || \
+ ((FLAG) == I2C_FLAG_MSL) || ((FLAG) == I2C_FLAG_SMBALERT) || \
+ ((FLAG) == I2C_FLAG_TIMEOUT) || ((FLAG) == I2C_FLAG_PECERR) || \
+ ((FLAG) == I2C_FLAG_OVR) || ((FLAG) == I2C_FLAG_AF) || \
+ ((FLAG) == I2C_FLAG_ARLO) || ((FLAG) == I2C_FLAG_BERR) || \
+ ((FLAG) == I2C_FLAG_TXE) || ((FLAG) == I2C_FLAG_RXNE) || \
+ ((FLAG) == I2C_FLAG_STOPF) || ((FLAG) == I2C_FLAG_ADD10) || \
+ ((FLAG) == I2C_FLAG_BTF) || ((FLAG) == I2C_FLAG_ADDR) || \
+ ((FLAG) == I2C_FLAG_SB))
+
+/* I2C Events */
+/* EV1 */
+#define I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED ((u32)0x00060082) /* TRA, BUSY, TXE and ADDR flags */
+#define I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED ((u32)0x00020002) /* BUSY and ADDR flags */
+#define I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED ((u32)0x00860080) /* DUALF, TRA, BUSY and TXE flags */
+#define I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED ((u32)0x00820000) /* DUALF and BUSY flags */
+#define I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED ((u32)0x00120000) /* GENCALL and BUSY flags */
+
+/* EV2 */
+#define I2C_EVENT_SLAVE_BYTE_RECEIVED ((u32)0x00020040) /* BUSY and RXNE flags */
+
+/* EV3 */
+#define I2C_EVENT_SLAVE_BYTE_TRANSMITTED ((u32)0x00060084) /* TRA, BUSY, TXE and BTF flags */
+
+/* EV4 */
+#define I2C_EVENT_SLAVE_STOP_DETECTED ((u32)0x00000010) /* STOPF flag */
+
+/* EV5 */
+#define I2C_EVENT_MASTER_MODE_SELECT ((u32)0x00030001) /* BUSY, MSL and SB flag */
+
+/* EV6 */
+#define I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED ((u32)0x00070082) /* BUSY, MSL, ADDR, TXE and TRA flags */
+#define I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED ((u32)0x00030002) /* BUSY, MSL and ADDR flags */
+
+/* EV7 */
+#define I2C_EVENT_MASTER_BYTE_RECEIVED ((u32)0x00030040) /* BUSY, MSL and RXNE flags */
+
+/* EV8 */
+#define I2C_EVENT_MASTER_BYTE_TRANSMITTED ((u32)0x00070084) /* TRA, BUSY, MSL, TXE and BTF flags */
+
+/* EV9 */
+#define I2C_EVENT_MASTER_MODE_ADDRESS10 ((u32)0x00030008) /* BUSY, MSL and ADD10 flags */
+
+/* EV3_2 */
+#define I2C_EVENT_SLAVE_ACK_FAILURE ((u32)0x00000400) /* AF flag */
+
+#define IS_I2C_EVENT(EVENT) (((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED) || \
+ ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED) || \
+ ((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED) || \
+ ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED) || \
+ ((EVENT) == I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED) || \
+ ((EVENT) == I2C_EVENT_SLAVE_BYTE_RECEIVED) || \
+ ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF)) || \
+ ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL)) || \
+ ((EVENT) == I2C_EVENT_SLAVE_BYTE_TRANSMITTED) || \
+ ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF)) || \
+ ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL)) || \
+ ((EVENT) == I2C_EVENT_SLAVE_STOP_DETECTED) || \
+ ((EVENT) == I2C_EVENT_MASTER_MODE_SELECT) || \
+ ((EVENT) == I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED) || \
+ ((EVENT) == I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED) || \
+ ((EVENT) == I2C_EVENT_MASTER_BYTE_RECEIVED) || \
+ ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTED) || \
+ ((EVENT) == I2C_EVENT_MASTER_MODE_ADDRESS10) || \
+ ((EVENT) == I2C_EVENT_SLAVE_ACK_FAILURE))
+
+/* I2C own address1 -----------------------------------------------------------*/
+#define IS_I2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x3FF)
+/* I2C clock speed ------------------------------------------------------------*/
+#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) >= 0x1) && ((SPEED) <= 400000))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void I2C_DeInit(I2C_TypeDef* I2Cx);
+void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct);
+void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct);
+void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, u8 Address);
+void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_ITConfig(I2C_TypeDef* I2Cx, u16 I2C_IT, FunctionalState NewState);
+void I2C_SendData(I2C_TypeDef* I2Cx, u8 Data);
+u8 I2C_ReceiveData(I2C_TypeDef* I2Cx);
+void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, u8 Address, u8 I2C_Direction);
+u16 I2C_ReadRegister(I2C_TypeDef* I2Cx, u8 I2C_Register);
+void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, u16 I2C_SMBusAlert);
+void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, u16 I2C_PECPosition);
+void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState);
+u8 I2C_GetPEC(I2C_TypeDef* I2Cx);
+void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, u16 I2C_DutyCycle);
+u32 I2C_GetLastEvent(I2C_TypeDef* I2Cx);
+ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, u32 I2C_EVENT);
+FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, u32 I2C_FLAG);
+void I2C_ClearFlag(I2C_TypeDef* I2Cx, u32 I2C_FLAG);
+ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, u32 I2C_IT);
+void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, u32 I2C_IT);
+
+#endif /*__STM32F10x_I2C_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_iwdg.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_iwdg.h new file mode 100755 index 0000000..0b71eae --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_iwdg.h @@ -0,0 +1,69 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_iwdg.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* IWDG firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IWDG_H
+#define __STM32F10x_IWDG_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Write access to IWDG_PR and IWDG_RLR registers */
+#define IWDG_WriteAccess_Enable ((u16)0x5555)
+#define IWDG_WriteAccess_Disable ((u16)0x0000)
+
+#define IS_IWDG_WRITE_ACCESS(ACCESS) (((ACCESS) == IWDG_WriteAccess_Enable) || \
+ ((ACCESS) == IWDG_WriteAccess_Disable))
+
+/* IWDG prescaler */
+#define IWDG_Prescaler_4 ((u8)0x00)
+#define IWDG_Prescaler_8 ((u8)0x01)
+#define IWDG_Prescaler_16 ((u8)0x02)
+#define IWDG_Prescaler_32 ((u8)0x03)
+#define IWDG_Prescaler_64 ((u8)0x04)
+#define IWDG_Prescaler_128 ((u8)0x05)
+#define IWDG_Prescaler_256 ((u8)0x06)
+
+#define IS_IWDG_PRESCALER(PRESCALER) (((PRESCALER) == IWDG_Prescaler_4) || \
+ ((PRESCALER) == IWDG_Prescaler_8) || \
+ ((PRESCALER) == IWDG_Prescaler_16) || \
+ ((PRESCALER) == IWDG_Prescaler_32) || \
+ ((PRESCALER) == IWDG_Prescaler_64) || \
+ ((PRESCALER) == IWDG_Prescaler_128)|| \
+ ((PRESCALER) == IWDG_Prescaler_256))
+
+/* IWDG Flag */
+#define IWDG_FLAG_PVU ((u16)0x0001)
+#define IWDG_FLAG_RVU ((u16)0x0002)
+
+#define IS_IWDG_FLAG(FLAG) (((FLAG) == IWDG_FLAG_PVU) || ((FLAG) == IWDG_FLAG_RVU))
+
+#define IS_IWDG_RELOAD(RELOAD) ((RELOAD) <= 0xFFF)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void IWDG_WriteAccessCmd(u16 IWDG_WriteAccess);
+void IWDG_SetPrescaler(u8 IWDG_Prescaler);
+void IWDG_SetReload(u16 Reload);
+void IWDG_ReloadCounter(void);
+void IWDG_Enable(void);
+FlagStatus IWDG_GetFlagStatus(u16 IWDG_FLAG);
+
+#endif /* __STM32F10x_IWDG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_lib.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_lib.h new file mode 100755 index 0000000..dfa3028 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_lib.h @@ -0,0 +1,124 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_lib.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file includes the peripherals header files in the
+* user application.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_LIB_H
+#define __STM32F10x_LIB_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+#ifdef _ADC
+ #include "stm32f10x_adc.h"
+#endif /*_ADC */
+
+#ifdef _BKP
+ #include "stm32f10x_bkp.h"
+#endif /*_BKP */
+
+#ifdef _CAN
+ #include "stm32f10x_can.h"
+#endif /*_CAN */
+
+#ifdef _CRC
+ #include "stm32f10x_crc.h"
+#endif /*_CRC */
+
+#ifdef _DAC
+ #include "stm32f10x_dac.h"
+#endif /*_DAC */
+
+#ifdef _DBGMCU
+ #include "stm32f10x_dbgmcu.h"
+#endif /*_DBGMCU */
+
+#ifdef _DMA
+ #include "stm32f10x_dma.h"
+#endif /*_DMA */
+
+#ifdef _EXTI
+ #include "stm32f10x_exti.h"
+#endif /*_EXTI */
+
+#ifdef _FLASH
+ #include "stm32f10x_flash.h"
+#endif /*_FLASH */
+
+#ifdef _FSMC
+ #include "stm32f10x_fsmc.h"
+#endif /*_FSMC */
+
+#ifdef _GPIO
+ #include "stm32f10x_gpio.h"
+#endif /*_GPIO */
+
+#ifdef _I2C
+ #include "stm32f10x_i2c.h"
+#endif /*_I2C */
+
+#ifdef _IWDG
+ #include "stm32f10x_iwdg.h"
+#endif /*_IWDG */
+
+#ifdef _NVIC
+ #include "stm32f10x_nvic.h"
+#endif /*_NVIC */
+
+#ifdef _PWR
+ #include "stm32f10x_pwr.h"
+#endif /*_PWR */
+
+#ifdef _RCC
+ #include "stm32f10x_rcc.h"
+#endif /*_RCC */
+
+#ifdef _RTC
+ #include "stm32f10x_rtc.h"
+#endif /*_RTC */
+
+#ifdef _SDIO
+ #include "stm32f10x_sdio.h"
+#endif /*_SDIO */
+
+#ifdef _SPI
+ #include "stm32f10x_spi.h"
+#endif /*_SPI */
+
+#ifdef _SysTick
+ #include "stm32f10x_systick.h"
+#endif /*_SysTick */
+
+#ifdef _TIM
+ #include "stm32f10x_tim.h"
+#endif /*_TIM */
+
+#ifdef _USART
+ #include "stm32f10x_usart.h"
+#endif /*_USART */
+
+#ifdef _WWDG
+ #include "stm32f10x_wwdg.h"
+#endif /*_WWDG */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void debug(void);
+
+#endif /* __STM32F10x_LIB_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_map.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_map.h new file mode 100755 index 0000000..506d1d2 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_map.h @@ -0,0 +1,1187 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_map.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the peripheral register's definitions
+* and memory mapping.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_MAP_H
+#define __STM32F10x_MAP_H
+
+#ifndef EXT
+ #define EXT extern
+#endif /* EXT */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_conf.h"
+#include "stm32f10x_type.h"
+#include "cortexm3_macro.h"
+
+/* Exported types ------------------------------------------------------------*/
+/******************************************************************************/
+/* Peripheral registers structures */
+/******************************************************************************/
+
+/*------------------------ Analog to Digital Converter -----------------------*/
+typedef struct
+{
+ vu32 SR;
+ vu32 CR1;
+ vu32 CR2;
+ vu32 SMPR1;
+ vu32 SMPR2;
+ vu32 JOFR1;
+ vu32 JOFR2;
+ vu32 JOFR3;
+ vu32 JOFR4;
+ vu32 HTR;
+ vu32 LTR;
+ vu32 SQR1;
+ vu32 SQR2;
+ vu32 SQR3;
+ vu32 JSQR;
+ vu32 JDR1;
+ vu32 JDR2;
+ vu32 JDR3;
+ vu32 JDR4;
+ vu32 DR;
+} ADC_TypeDef;
+
+/*------------------------ Backup Registers ----------------------------------*/
+typedef struct
+{
+ u32 RESERVED0;
+ vu16 DR1;
+ u16 RESERVED1;
+ vu16 DR2;
+ u16 RESERVED2;
+ vu16 DR3;
+ u16 RESERVED3;
+ vu16 DR4;
+ u16 RESERVED4;
+ vu16 DR5;
+ u16 RESERVED5;
+ vu16 DR6;
+ u16 RESERVED6;
+ vu16 DR7;
+ u16 RESERVED7;
+ vu16 DR8;
+ u16 RESERVED8;
+ vu16 DR9;
+ u16 RESERVED9;
+ vu16 DR10;
+ u16 RESERVED10;
+ vu16 RTCCR;
+ u16 RESERVED11;
+ vu16 CR;
+ u16 RESERVED12;
+ vu16 CSR;
+ u16 RESERVED13[5];
+ vu16 DR11;
+ u16 RESERVED14;
+ vu16 DR12;
+ u16 RESERVED15;
+ vu16 DR13;
+ u16 RESERVED16;
+ vu16 DR14;
+ u16 RESERVED17;
+ vu16 DR15;
+ u16 RESERVED18;
+ vu16 DR16;
+ u16 RESERVED19;
+ vu16 DR17;
+ u16 RESERVED20;
+ vu16 DR18;
+ u16 RESERVED21;
+ vu16 DR19;
+ u16 RESERVED22;
+ vu16 DR20;
+ u16 RESERVED23;
+ vu16 DR21;
+ u16 RESERVED24;
+ vu16 DR22;
+ u16 RESERVED25;
+ vu16 DR23;
+ u16 RESERVED26;
+ vu16 DR24;
+ u16 RESERVED27;
+ vu16 DR25;
+ u16 RESERVED28;
+ vu16 DR26;
+ u16 RESERVED29;
+ vu16 DR27;
+ u16 RESERVED30;
+ vu16 DR28;
+ u16 RESERVED31;
+ vu16 DR29;
+ u16 RESERVED32;
+ vu16 DR30;
+ u16 RESERVED33;
+ vu16 DR31;
+ u16 RESERVED34;
+ vu16 DR32;
+ u16 RESERVED35;
+ vu16 DR33;
+ u16 RESERVED36;
+ vu16 DR34;
+ u16 RESERVED37;
+ vu16 DR35;
+ u16 RESERVED38;
+ vu16 DR36;
+ u16 RESERVED39;
+ vu16 DR37;
+ u16 RESERVED40;
+ vu16 DR38;
+ u16 RESERVED41;
+ vu16 DR39;
+ u16 RESERVED42;
+ vu16 DR40;
+ u16 RESERVED43;
+ vu16 DR41;
+ u16 RESERVED44;
+ vu16 DR42;
+ u16 RESERVED45;
+} BKP_TypeDef;
+
+/*------------------------ Controller Area Network ---------------------------*/
+typedef struct
+{
+ vu32 TIR;
+ vu32 TDTR;
+ vu32 TDLR;
+ vu32 TDHR;
+} CAN_TxMailBox_TypeDef;
+
+typedef struct
+{
+ vu32 RIR;
+ vu32 RDTR;
+ vu32 RDLR;
+ vu32 RDHR;
+} CAN_FIFOMailBox_TypeDef;
+
+typedef struct
+{
+ vu32 FR1;
+ vu32 FR2;
+} CAN_FilterRegister_TypeDef;
+
+typedef struct
+{
+ vu32 MCR;
+ vu32 MSR;
+ vu32 TSR;
+ vu32 RF0R;
+ vu32 RF1R;
+ vu32 IER;
+ vu32 ESR;
+ vu32 BTR;
+ u32 RESERVED0[88];
+ CAN_TxMailBox_TypeDef sTxMailBox[3];
+ CAN_FIFOMailBox_TypeDef sFIFOMailBox[2];
+ u32 RESERVED1[12];
+ vu32 FMR;
+ vu32 FM1R;
+ u32 RESERVED2;
+ vu32 FS1R;
+ u32 RESERVED3;
+ vu32 FFA1R;
+ u32 RESERVED4;
+ vu32 FA1R;
+ u32 RESERVED5[8];
+ CAN_FilterRegister_TypeDef sFilterRegister[14];
+} CAN_TypeDef;
+
+/*------------------------ CRC calculation unit ------------------------------*/
+typedef struct
+{
+ vu32 DR;
+ vu8 IDR;
+ u8 RESERVED0;
+ u16 RESERVED1;
+ vu32 CR;
+} CRC_TypeDef;
+
+
+/*------------------------ Digital to Analog Converter -----------------------*/
+typedef struct
+{
+ vu32 CR;
+ vu32 SWTRIGR;
+ vu32 DHR12R1;
+ vu32 DHR12L1;
+ vu32 DHR8R1;
+ vu32 DHR12R2;
+ vu32 DHR12L2;
+ vu32 DHR8R2;
+ vu32 DHR12RD;
+ vu32 DHR12LD;
+ vu32 DHR8RD;
+ vu32 DOR1;
+ vu32 DOR2;
+} DAC_TypeDef;
+
+/*------------------------ Debug MCU -----------------------------------------*/
+typedef struct
+{
+ vu32 IDCODE;
+ vu32 CR;
+}DBGMCU_TypeDef;
+
+/*------------------------ DMA Controller ------------------------------------*/
+typedef struct
+{
+ vu32 CCR;
+ vu32 CNDTR;
+ vu32 CPAR;
+ vu32 CMAR;
+} DMA_Channel_TypeDef;
+
+typedef struct
+{
+ vu32 ISR;
+ vu32 IFCR;
+} DMA_TypeDef;
+
+/*------------------------ External Interrupt/Event Controller ---------------*/
+typedef struct
+{
+ vu32 IMR;
+ vu32 EMR;
+ vu32 RTSR;
+ vu32 FTSR;
+ vu32 SWIER;
+ vu32 PR;
+} EXTI_TypeDef;
+
+/*------------------------ FLASH and Option Bytes Registers ------------------*/
+typedef struct
+{
+ vu32 ACR;
+ vu32 KEYR;
+ vu32 OPTKEYR;
+ vu32 SR;
+ vu32 CR;
+ vu32 AR;
+ vu32 RESERVED;
+ vu32 OBR;
+ vu32 WRPR;
+} FLASH_TypeDef;
+
+typedef struct
+{
+ vu16 RDP;
+ vu16 USER;
+ vu16 Data0;
+ vu16 Data1;
+ vu16 WRP0;
+ vu16 WRP1;
+ vu16 WRP2;
+ vu16 WRP3;
+} OB_TypeDef;
+
+/*------------------------ Flexible Static Memory Controller -----------------*/
+typedef struct
+{
+ vu32 BTCR[8];
+} FSMC_Bank1_TypeDef;
+
+typedef struct
+{
+ vu32 BWTR[7];
+} FSMC_Bank1E_TypeDef;
+
+typedef struct
+{
+ vu32 PCR2;
+ vu32 SR2;
+ vu32 PMEM2;
+ vu32 PATT2;
+ u32 RESERVED0;
+ vu32 ECCR2;
+} FSMC_Bank2_TypeDef;
+
+typedef struct
+{
+ vu32 PCR3;
+ vu32 SR3;
+ vu32 PMEM3;
+ vu32 PATT3;
+ u32 RESERVED0;
+ vu32 ECCR3;
+} FSMC_Bank3_TypeDef;
+
+typedef struct
+{
+ vu32 PCR4;
+ vu32 SR4;
+ vu32 PMEM4;
+ vu32 PATT4;
+ vu32 PIO4;
+} FSMC_Bank4_TypeDef;
+
+/*------------------------ General Purpose and Alternate Function IO ---------*/
+typedef struct
+{
+ vu32 CRL;
+ vu32 CRH;
+ vu32 IDR;
+ vu32 ODR;
+ vu32 BSRR;
+ vu32 BRR;
+ vu32 LCKR;
+} GPIO_TypeDef;
+
+typedef struct
+{
+ vu32 EVCR;
+ vu32 MAPR;
+ vu32 EXTICR[4];
+} AFIO_TypeDef;
+
+/*------------------------ Inter-integrated Circuit Interface ----------------*/
+typedef struct
+{
+ vu16 CR1;
+ u16 RESERVED0;
+ vu16 CR2;
+ u16 RESERVED1;
+ vu16 OAR1;
+ u16 RESERVED2;
+ vu16 OAR2;
+ u16 RESERVED3;
+ vu16 DR;
+ u16 RESERVED4;
+ vu16 SR1;
+ u16 RESERVED5;
+ vu16 SR2;
+ u16 RESERVED6;
+ vu16 CCR;
+ u16 RESERVED7;
+ vu16 TRISE;
+ u16 RESERVED8;
+} I2C_TypeDef;
+
+/*------------------------ Independent WATCHDOG ------------------------------*/
+typedef struct
+{
+ vu32 KR;
+ vu32 PR;
+ vu32 RLR;
+ vu32 SR;
+} IWDG_TypeDef;
+
+/*------------------------ Nested Vectored Interrupt Controller --------------*/
+typedef struct
+{
+ vu32 ISER[2];
+ u32 RESERVED0[30];
+ vu32 ICER[2];
+ u32 RSERVED1[30];
+ vu32 ISPR[2];
+ u32 RESERVED2[30];
+ vu32 ICPR[2];
+ u32 RESERVED3[30];
+ vu32 IABR[2];
+ u32 RESERVED4[62];
+ vu32 IPR[15];
+} NVIC_TypeDef;
+
+typedef struct
+{
+ vuc32 CPUID;
+ vu32 ICSR;
+ vu32 VTOR;
+ vu32 AIRCR;
+ vu32 SCR;
+ vu32 CCR;
+ vu32 SHPR[3];
+ vu32 SHCSR;
+ vu32 CFSR;
+ vu32 HFSR;
+ vu32 DFSR;
+ vu32 MMFAR;
+ vu32 BFAR;
+ vu32 AFSR;
+} SCB_TypeDef;
+
+/*------------------------ Power Control -------------------------------------*/
+typedef struct
+{
+ vu32 CR;
+ vu32 CSR;
+} PWR_TypeDef;
+
+/*------------------------ Reset and Clock Control ---------------------------*/
+typedef struct
+{
+ vu32 CR;
+ vu32 CFGR;
+ vu32 CIR;
+ vu32 APB2RSTR;
+ vu32 APB1RSTR;
+ vu32 AHBENR;
+ vu32 APB2ENR;
+ vu32 APB1ENR;
+ vu32 BDCR;
+ vu32 CSR;
+} RCC_TypeDef;
+
+/*------------------------ Real-Time Clock -----------------------------------*/
+typedef struct
+{
+ vu16 CRH;
+ u16 RESERVED0;
+ vu16 CRL;
+ u16 RESERVED1;
+ vu16 PRLH;
+ u16 RESERVED2;
+ vu16 PRLL;
+ u16 RESERVED3;
+ vu16 DIVH;
+ u16 RESERVED4;
+ vu16 DIVL;
+ u16 RESERVED5;
+ vu16 CNTH;
+ u16 RESERVED6;
+ vu16 CNTL;
+ u16 RESERVED7;
+ vu16 ALRH;
+ u16 RESERVED8;
+ vu16 ALRL;
+ u16 RESERVED9;
+} RTC_TypeDef;
+
+/*------------------------ SD host Interface ---------------------------------*/
+typedef struct
+{
+ vu32 POWER;
+ vu32 CLKCR;
+ vu32 ARG;
+ vu32 CMD;
+ vuc32 RESPCMD;
+ vuc32 RESP1;
+ vuc32 RESP2;
+ vuc32 RESP3;
+ vuc32 RESP4;
+ vu32 DTIMER;
+ vu32 DLEN;
+ vu32 DCTRL;
+ vuc32 DCOUNT;
+ vuc32 STA;
+ vu32 ICR;
+ vu32 MASK;
+ u32 RESERVED0[2];
+ vuc32 FIFOCNT;
+ u32 RESERVED1[13];
+ vu32 FIFO;
+} SDIO_TypeDef;
+
+/*------------------------ Serial Peripheral Interface -----------------------*/
+typedef struct
+{
+ vu16 CR1;
+ u16 RESERVED0;
+ vu16 CR2;
+ u16 RESERVED1;
+ vu16 SR;
+ u16 RESERVED2;
+ vu16 DR;
+ u16 RESERVED3;
+ vu16 CRCPR;
+ u16 RESERVED4;
+ vu16 RXCRCR;
+ u16 RESERVED5;
+ vu16 TXCRCR;
+ u16 RESERVED6;
+ vu16 I2SCFGR;
+ u16 RESERVED7;
+ vu16 I2SPR;
+ u16 RESERVED8;
+} SPI_TypeDef;
+
+/*------------------------ SystemTick ----------------------------------------*/
+typedef struct
+{
+ vu32 CTRL;
+ vu32 LOAD;
+ vu32 VAL;
+ vuc32 CALIB;
+} SysTick_TypeDef;
+
+/*------------------------ TIM -----------------------------------------------*/
+typedef struct
+{
+ vu16 CR1;
+ u16 RESERVED0;
+ vu16 CR2;
+ u16 RESERVED1;
+ vu16 SMCR;
+ u16 RESERVED2;
+ vu16 DIER;
+ u16 RESERVED3;
+ vu16 SR;
+ u16 RESERVED4;
+ vu16 EGR;
+ u16 RESERVED5;
+ vu16 CCMR1;
+ u16 RESERVED6;
+ vu16 CCMR2;
+ u16 RESERVED7;
+ vu16 CCER;
+ u16 RESERVED8;
+ vu16 CNT;
+ u16 RESERVED9;
+ vu16 PSC;
+ u16 RESERVED10;
+ vu16 ARR;
+ u16 RESERVED11;
+ vu16 RCR;
+ u16 RESERVED12;
+ vu16 CCR1;
+ u16 RESERVED13;
+ vu16 CCR2;
+ u16 RESERVED14;
+ vu16 CCR3;
+ u16 RESERVED15;
+ vu16 CCR4;
+ u16 RESERVED16;
+ vu16 BDTR;
+ u16 RESERVED17;
+ vu16 DCR;
+ u16 RESERVED18;
+ vu16 DMAR;
+ u16 RESERVED19;
+} TIM_TypeDef;
+
+/*----------------- Universal Synchronous Asynchronous Receiver Transmitter --*/
+typedef struct
+{
+ vu16 SR;
+ u16 RESERVED0;
+ vu16 DR;
+ u16 RESERVED1;
+ vu16 BRR;
+ u16 RESERVED2;
+ vu16 CR1;
+ u16 RESERVED3;
+ vu16 CR2;
+ u16 RESERVED4;
+ vu16 CR3;
+ u16 RESERVED5;
+ vu16 GTPR;
+ u16 RESERVED6;
+} USART_TypeDef;
+
+/*------------------------ Window WATCHDOG -----------------------------------*/
+typedef struct
+{
+ vu32 CR;
+ vu32 CFR;
+ vu32 SR;
+} WWDG_TypeDef;
+
+/******************************************************************************/
+/* Peripheral memory map */
+/******************************************************************************/
+/* Peripheral and SRAM base address in the alias region */
+#define PERIPH_BB_BASE ((u32)0x42000000)
+#define SRAM_BB_BASE ((u32)0x22000000)
+
+/* Peripheral and SRAM base address in the bit-band region */
+#define SRAM_BASE ((u32)0x20000000)
+#define PERIPH_BASE ((u32)0x40000000)
+
+/* FSMC registers base address */
+#define FSMC_R_BASE ((u32)0xA0000000)
+
+/* Peripheral memory map */
+#define APB1PERIPH_BASE PERIPH_BASE
+#define APB2PERIPH_BASE (PERIPH_BASE + 0x10000)
+#define AHBPERIPH_BASE (PERIPH_BASE + 0x20000)
+
+#define TIM2_BASE (APB1PERIPH_BASE + 0x0000)
+#define TIM3_BASE (APB1PERIPH_BASE + 0x0400)
+#define TIM4_BASE (APB1PERIPH_BASE + 0x0800)
+#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00)
+#define TIM6_BASE (APB1PERIPH_BASE + 0x1000)
+#define TIM7_BASE (APB1PERIPH_BASE + 0x1400)
+#define RTC_BASE (APB1PERIPH_BASE + 0x2800)
+#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00)
+#define IWDG_BASE (APB1PERIPH_BASE + 0x3000)
+#define SPI2_BASE (APB1PERIPH_BASE + 0x3800)
+#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00)
+#define USART2_BASE (APB1PERIPH_BASE + 0x4400)
+#define USART3_BASE (APB1PERIPH_BASE + 0x4800)
+#define UART4_BASE (APB1PERIPH_BASE + 0x4C00)
+#define UART5_BASE (APB1PERIPH_BASE + 0x5000)
+#define I2C1_BASE (APB1PERIPH_BASE + 0x5400)
+#define I2C2_BASE (APB1PERIPH_BASE + 0x5800)
+#define CAN_BASE (APB1PERIPH_BASE + 0x6400)
+#define BKP_BASE (APB1PERIPH_BASE + 0x6C00)
+#define PWR_BASE (APB1PERIPH_BASE + 0x7000)
+#define DAC_BASE (APB1PERIPH_BASE + 0x7400)
+
+#define AFIO_BASE (APB2PERIPH_BASE + 0x0000)
+#define EXTI_BASE (APB2PERIPH_BASE + 0x0400)
+#define GPIOA_BASE (APB2PERIPH_BASE + 0x0800)
+#define GPIOB_BASE (APB2PERIPH_BASE + 0x0C00)
+#define GPIOC_BASE (APB2PERIPH_BASE + 0x1000)
+#define GPIOD_BASE (APB2PERIPH_BASE + 0x1400)
+#define GPIOE_BASE (APB2PERIPH_BASE + 0x1800)
+#define GPIOF_BASE (APB2PERIPH_BASE + 0x1C00)
+#define GPIOG_BASE (APB2PERIPH_BASE + 0x2000)
+#define ADC1_BASE (APB2PERIPH_BASE + 0x2400)
+#define ADC2_BASE (APB2PERIPH_BASE + 0x2800)
+#define TIM1_BASE (APB2PERIPH_BASE + 0x2C00)
+#define SPI1_BASE (APB2PERIPH_BASE + 0x3000)
+#define TIM8_BASE (APB2PERIPH_BASE + 0x3400)
+#define USART1_BASE (APB2PERIPH_BASE + 0x3800)
+#define ADC3_BASE (APB2PERIPH_BASE + 0x3C00)
+
+#define SDIO_BASE (PERIPH_BASE + 0x18000)
+
+#define DMA1_BASE (AHBPERIPH_BASE + 0x0000)
+#define DMA1_Channel1_BASE (AHBPERIPH_BASE + 0x0008)
+#define DMA1_Channel2_BASE (AHBPERIPH_BASE + 0x001C)
+#define DMA1_Channel3_BASE (AHBPERIPH_BASE + 0x0030)
+#define DMA1_Channel4_BASE (AHBPERIPH_BASE + 0x0044)
+#define DMA1_Channel5_BASE (AHBPERIPH_BASE + 0x0058)
+#define DMA1_Channel6_BASE (AHBPERIPH_BASE + 0x006C)
+#define DMA1_Channel7_BASE (AHBPERIPH_BASE + 0x0080)
+#define DMA2_BASE (AHBPERIPH_BASE + 0x0400)
+#define DMA2_Channel1_BASE (AHBPERIPH_BASE + 0x0408)
+#define DMA2_Channel2_BASE (AHBPERIPH_BASE + 0x041C)
+#define DMA2_Channel3_BASE (AHBPERIPH_BASE + 0x0430)
+#define DMA2_Channel4_BASE (AHBPERIPH_BASE + 0x0444)
+#define DMA2_Channel5_BASE (AHBPERIPH_BASE + 0x0458)
+#define RCC_BASE (AHBPERIPH_BASE + 0x1000)
+#define CRC_BASE (AHBPERIPH_BASE + 0x3000)
+
+/* Flash registers base address */
+#define FLASH_R_BASE (AHBPERIPH_BASE + 0x2000)
+/* Flash Option Bytes base address */
+#define OB_BASE ((u32)0x1FFFF800)
+
+/* FSMC Bankx registers base address */
+#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000)
+#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104)
+#define FSMC_Bank2_R_BASE (FSMC_R_BASE + 0x0060)
+#define FSMC_Bank3_R_BASE (FSMC_R_BASE + 0x0080)
+#define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0)
+
+/* Debug MCU registers base address */
+#define DBGMCU_BASE ((u32)0xE0042000)
+
+/* System Control Space memory map */
+#define SCS_BASE ((u32)0xE000E000)
+
+#define SysTick_BASE (SCS_BASE + 0x0010)
+#define NVIC_BASE (SCS_BASE + 0x0100)
+#define SCB_BASE (SCS_BASE + 0x0D00)
+
+/******************************************************************************/
+/* Peripheral declaration */
+/******************************************************************************/
+
+/*------------------------ Non Debug Mode ------------------------------------*/
+#ifndef DEBUG
+#ifdef _TIM2
+ #define TIM2 ((TIM_TypeDef *) TIM2_BASE)
+#endif /*_TIM2 */
+
+#ifdef _TIM3
+ #define TIM3 ((TIM_TypeDef *) TIM3_BASE)
+#endif /*_TIM3 */
+
+#ifdef _TIM4
+ #define TIM4 ((TIM_TypeDef *) TIM4_BASE)
+#endif /*_TIM4 */
+
+#ifdef _TIM5
+ #define TIM5 ((TIM_TypeDef *) TIM5_BASE)
+#endif /*_TIM5 */
+
+#ifdef _TIM6
+ #define TIM6 ((TIM_TypeDef *) TIM6_BASE)
+#endif /*_TIM6 */
+
+#ifdef _TIM7
+ #define TIM7 ((TIM_TypeDef *) TIM7_BASE)
+#endif /*_TIM7 */
+
+#ifdef _RTC
+ #define RTC ((RTC_TypeDef *) RTC_BASE)
+#endif /*_RTC */
+
+#ifdef _WWDG
+ #define WWDG ((WWDG_TypeDef *) WWDG_BASE)
+#endif /*_WWDG */
+
+#ifdef _IWDG
+ #define IWDG ((IWDG_TypeDef *) IWDG_BASE)
+#endif /*_IWDG */
+
+#ifdef _SPI2
+ #define SPI2 ((SPI_TypeDef *) SPI2_BASE)
+#endif /*_SPI2 */
+
+#ifdef _SPI3
+ #define SPI3 ((SPI_TypeDef *) SPI3_BASE)
+#endif /*_SPI3 */
+
+#ifdef _USART2
+ #define USART2 ((USART_TypeDef *) USART2_BASE)
+#endif /*_USART2 */
+
+#ifdef _USART3
+ #define USART3 ((USART_TypeDef *) USART3_BASE)
+#endif /*_USART3 */
+
+#ifdef _UART4
+ #define UART4 ((USART_TypeDef *) UART4_BASE)
+#endif /*_UART4 */
+
+#ifdef _UART5
+ #define UART5 ((USART_TypeDef *) UART5_BASE)
+#endif /*_USART5 */
+
+#ifdef _I2C1
+ #define I2C1 ((I2C_TypeDef *) I2C1_BASE)
+#endif /*_I2C1 */
+
+#ifdef _I2C2
+ #define I2C2 ((I2C_TypeDef *) I2C2_BASE)
+#endif /*_I2C2 */
+
+#ifdef _CAN
+ #define CAN ((CAN_TypeDef *) CAN_BASE)
+#endif /*_CAN */
+
+#ifdef _BKP
+ #define BKP ((BKP_TypeDef *) BKP_BASE)
+#endif /*_BKP */
+
+#ifdef _PWR
+ #define PWR ((PWR_TypeDef *) PWR_BASE)
+#endif /*_PWR */
+
+#ifdef _DAC
+ #define DAC ((DAC_TypeDef *) DAC_BASE)
+#endif /*_DAC */
+
+#ifdef _AFIO
+ #define AFIO ((AFIO_TypeDef *) AFIO_BASE)
+#endif /*_AFIO */
+
+#ifdef _EXTI
+ #define EXTI ((EXTI_TypeDef *) EXTI_BASE)
+#endif /*_EXTI */
+
+#ifdef _GPIOA
+ #define GPIOA ((GPIO_TypeDef *) GPIOA_BASE)
+#endif /*_GPIOA */
+
+#ifdef _GPIOB
+ #define GPIOB ((GPIO_TypeDef *) GPIOB_BASE)
+#endif /*_GPIOB */
+
+#ifdef _GPIOC
+ #define GPIOC ((GPIO_TypeDef *) GPIOC_BASE)
+#endif /*_GPIOC */
+
+#ifdef _GPIOD
+ #define GPIOD ((GPIO_TypeDef *) GPIOD_BASE)
+#endif /*_GPIOD */
+
+#ifdef _GPIOE
+ #define GPIOE ((GPIO_TypeDef *) GPIOE_BASE)
+#endif /*_GPIOE */
+
+#ifdef _GPIOF
+ #define GPIOF ((GPIO_TypeDef *) GPIOF_BASE)
+#endif /*_GPIOF */
+
+#ifdef _GPIOG
+ #define GPIOG ((GPIO_TypeDef *) GPIOG_BASE)
+#endif /*_GPIOG */
+
+#ifdef _ADC1
+ #define ADC1 ((ADC_TypeDef *) ADC1_BASE)
+#endif /*_ADC1 */
+
+#ifdef _ADC2
+ #define ADC2 ((ADC_TypeDef *) ADC2_BASE)
+#endif /*_ADC2 */
+
+#ifdef _TIM1
+ #define TIM1 ((TIM_TypeDef *) TIM1_BASE)
+#endif /*_TIM1 */
+
+#ifdef _SPI1
+ #define SPI1 ((SPI_TypeDef *) SPI1_BASE)
+#endif /*_SPI1 */
+
+#ifdef _TIM8
+ #define TIM8 ((TIM_TypeDef *) TIM8_BASE)
+#endif /*_TIM8 */
+
+#ifdef _USART1
+ #define USART1 ((USART_TypeDef *) USART1_BASE)
+#endif /*_USART1 */
+
+#ifdef _ADC3
+ #define ADC3 ((ADC_TypeDef *) ADC3_BASE)
+#endif /*_ADC3 */
+
+#ifdef _SDIO
+ #define SDIO ((SDIO_TypeDef *) SDIO_BASE)
+#endif /*_SDIO */
+
+#ifdef _DMA
+ #define DMA1 ((DMA_TypeDef *) DMA1_BASE)
+ #define DMA2 ((DMA_TypeDef *) DMA2_BASE)
+#endif /*_DMA */
+
+#ifdef _DMA1_Channel1
+ #define DMA1_Channel1 ((DMA_Channel_TypeDef *) DMA1_Channel1_BASE)
+#endif /*_DMA1_Channel1 */
+
+#ifdef _DMA1_Channel2
+ #define DMA1_Channel2 ((DMA_Channel_TypeDef *) DMA1_Channel2_BASE)
+#endif /*_DMA1_Channel2 */
+
+#ifdef _DMA1_Channel3
+ #define DMA1_Channel3 ((DMA_Channel_TypeDef *) DMA1_Channel3_BASE)
+#endif /*_DMA1_Channel3 */
+
+#ifdef _DMA1_Channel4
+ #define DMA1_Channel4 ((DMA_Channel_TypeDef *) DMA1_Channel4_BASE)
+#endif /*_DMA1_Channel4 */
+
+#ifdef _DMA1_Channel5
+ #define DMA1_Channel5 ((DMA_Channel_TypeDef *) DMA1_Channel5_BASE)
+#endif /*_DMA1_Channel5 */
+
+#ifdef _DMA1_Channel6
+ #define DMA1_Channel6 ((DMA_Channel_TypeDef *) DMA1_Channel6_BASE)
+#endif /*_DMA1_Channel6 */
+
+#ifdef _DMA1_Channel7
+ #define DMA1_Channel7 ((DMA_Channel_TypeDef *) DMA1_Channel7_BASE)
+#endif /*_DMA1_Channel7 */
+
+#ifdef _DMA2_Channel1
+ #define DMA2_Channel1 ((DMA_Channel_TypeDef *) DMA2_Channel1_BASE)
+#endif /*_DMA2_Channel1 */
+
+#ifdef _DMA2_Channel2
+ #define DMA2_Channel2 ((DMA_Channel_TypeDef *) DMA2_Channel2_BASE)
+#endif /*_DMA2_Channel2 */
+
+#ifdef _DMA2_Channel3
+ #define DMA2_Channel3 ((DMA_Channel_TypeDef *) DMA2_Channel3_BASE)
+#endif /*_DMA2_Channel3 */
+
+#ifdef _DMA2_Channel4
+ #define DMA2_Channel4 ((DMA_Channel_TypeDef *) DMA2_Channel4_BASE)
+#endif /*_DMA2_Channel4 */
+
+#ifdef _DMA2_Channel5
+ #define DMA2_Channel5 ((DMA_Channel_TypeDef *) DMA2_Channel5_BASE)
+#endif /*_DMA2_Channel5 */
+
+#ifdef _RCC
+ #define RCC ((RCC_TypeDef *) RCC_BASE)
+#endif /*_RCC */
+
+#ifdef _CRC
+ #define CRC ((CRC_TypeDef *) CRC_BASE)
+#endif /*_CRC */
+
+#ifdef _FLASH
+ #define FLASH ((FLASH_TypeDef *) FLASH_R_BASE)
+ #define OB ((OB_TypeDef *) OB_BASE)
+#endif /*_FLASH */
+
+#ifdef _FSMC
+ #define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE)
+ #define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE)
+ #define FSMC_Bank2 ((FSMC_Bank2_TypeDef *) FSMC_Bank2_R_BASE)
+ #define FSMC_Bank3 ((FSMC_Bank3_TypeDef *) FSMC_Bank3_R_BASE)
+ #define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE)
+#endif /*_FSMC */
+
+#ifdef _DBGMCU
+ #define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE)
+#endif /*_DBGMCU */
+
+#ifdef _SysTick
+ #define SysTick ((SysTick_TypeDef *) SysTick_BASE)
+#endif /*_SysTick */
+
+#ifdef _NVIC
+ #define NVIC ((NVIC_TypeDef *) NVIC_BASE)
+ #define SCB ((SCB_TypeDef *) SCB_BASE)
+#endif /*_NVIC */
+
+/*------------------------ Debug Mode ----------------------------------------*/
+#else /* DEBUG */
+#ifdef _TIM2
+ EXT TIM_TypeDef *TIM2;
+#endif /*_TIM2 */
+
+#ifdef _TIM3
+ EXT TIM_TypeDef *TIM3;
+#endif /*_TIM3 */
+
+#ifdef _TIM4
+ EXT TIM_TypeDef *TIM4;
+#endif /*_TIM4 */
+
+#ifdef _TIM5
+ EXT TIM_TypeDef *TIM5;
+#endif /*_TIM5 */
+
+#ifdef _TIM6
+ EXT TIM_TypeDef *TIM6;
+#endif /*_TIM6 */
+
+#ifdef _TIM7
+ EXT TIM_TypeDef *TIM7;
+#endif /*_TIM7 */
+
+#ifdef _RTC
+ EXT RTC_TypeDef *RTC;
+#endif /*_RTC */
+
+#ifdef _WWDG
+ EXT WWDG_TypeDef *WWDG;
+#endif /*_WWDG */
+
+#ifdef _IWDG
+ EXT IWDG_TypeDef *IWDG;
+#endif /*_IWDG */
+
+#ifdef _SPI2
+ EXT SPI_TypeDef *SPI2;
+#endif /*_SPI2 */
+
+#ifdef _SPI3
+ EXT SPI_TypeDef *SPI3;
+#endif /*_SPI3 */
+
+#ifdef _USART2
+ EXT USART_TypeDef *USART2;
+#endif /*_USART2 */
+
+#ifdef _USART3
+ EXT USART_TypeDef *USART3;
+#endif /*_USART3 */
+
+#ifdef _UART4
+ EXT USART_TypeDef *UART4;
+#endif /*_UART4 */
+
+#ifdef _UART5
+ EXT USART_TypeDef *UART5;
+#endif /*_UART5 */
+
+#ifdef _I2C1
+ EXT I2C_TypeDef *I2C1;
+#endif /*_I2C1 */
+
+#ifdef _I2C2
+ EXT I2C_TypeDef *I2C2;
+#endif /*_I2C2 */
+
+#ifdef _CAN
+ EXT CAN_TypeDef *CAN;
+#endif /*_CAN */
+
+#ifdef _BKP
+ EXT BKP_TypeDef *BKP;
+#endif /*_BKP */
+
+#ifdef _PWR
+ EXT PWR_TypeDef *PWR;
+#endif /*_PWR */
+
+#ifdef _DAC
+ EXT DAC_TypeDef *DAC;
+#endif /*_DAC */
+
+#ifdef _AFIO
+ EXT AFIO_TypeDef *AFIO;
+#endif /*_AFIO */
+
+#ifdef _EXTI
+ EXT EXTI_TypeDef *EXTI;
+#endif /*_EXTI */
+
+#ifdef _GPIOA
+ EXT GPIO_TypeDef *GPIOA;
+#endif /*_GPIOA */
+
+#ifdef _GPIOB
+ EXT GPIO_TypeDef *GPIOB;
+#endif /*_GPIOB */
+
+#ifdef _GPIOC
+ EXT GPIO_TypeDef *GPIOC;
+#endif /*_GPIOC */
+
+#ifdef _GPIOD
+ EXT GPIO_TypeDef *GPIOD;
+#endif /*_GPIOD */
+
+#ifdef _GPIOE
+ EXT GPIO_TypeDef *GPIOE;
+#endif /*_GPIOE */
+
+#ifdef _GPIOF
+ EXT GPIO_TypeDef *GPIOF;
+#endif /*_GPIOF */
+
+#ifdef _GPIOG
+ EXT GPIO_TypeDef *GPIOG;
+#endif /*_GPIOG */
+
+#ifdef _ADC1
+ EXT ADC_TypeDef *ADC1;
+#endif /*_ADC1 */
+
+#ifdef _ADC2
+ EXT ADC_TypeDef *ADC2;
+#endif /*_ADC2 */
+
+#ifdef _TIM1
+ EXT TIM_TypeDef *TIM1;
+#endif /*_TIM1 */
+
+#ifdef _SPI1
+ EXT SPI_TypeDef *SPI1;
+#endif /*_SPI1 */
+
+#ifdef _TIM8
+ EXT TIM_TypeDef *TIM8;
+#endif /*_TIM8 */
+
+#ifdef _USART1
+ EXT USART_TypeDef *USART1;
+#endif /*_USART1 */
+
+#ifdef _ADC3
+ EXT ADC_TypeDef *ADC3;
+#endif /*_ADC3 */
+
+#ifdef _SDIO
+ EXT SDIO_TypeDef *SDIO;
+#endif /*_SDIO */
+
+#ifdef _DMA
+ EXT DMA_TypeDef *DMA1;
+ EXT DMA_TypeDef *DMA2;
+#endif /*_DMA */
+
+#ifdef _DMA1_Channel1
+ EXT DMA_Channel_TypeDef *DMA1_Channel1;
+#endif /*_DMA1_Channel1 */
+
+#ifdef _DMA1_Channel2
+ EXT DMA_Channel_TypeDef *DMA1_Channel2;
+#endif /*_DMA1_Channel2 */
+
+#ifdef _DMA1_Channel3
+ EXT DMA_Channel_TypeDef *DMA1_Channel3;
+#endif /*_DMA1_Channel3 */
+
+#ifdef _DMA1_Channel4
+ EXT DMA_Channel_TypeDef *DMA1_Channel4;
+#endif /*_DMA1_Channel4 */
+
+#ifdef _DMA1_Channel5
+ EXT DMA_Channel_TypeDef *DMA1_Channel5;
+#endif /*_DMA1_Channel5 */
+
+#ifdef _DMA1_Channel6
+ EXT DMA_Channel_TypeDef *DMA1_Channel6;
+#endif /*_DMA1_Channel6 */
+
+#ifdef _DMA1_Channel7
+ EXT DMA_Channel_TypeDef *DMA1_Channel7;
+#endif /*_DMA1_Channel7 */
+
+#ifdef _DMA2_Channel1
+ EXT DMA_Channel_TypeDef *DMA2_Channel1;
+#endif /*_DMA2_Channel1 */
+
+#ifdef _DMA2_Channel2
+ EXT DMA_Channel_TypeDef *DMA2_Channel2;
+#endif /*_DMA2_Channel2 */
+
+#ifdef _DMA2_Channel3
+ EXT DMA_Channel_TypeDef *DMA2_Channel3;
+#endif /*_DMA2_Channel3 */
+
+#ifdef _DMA2_Channel4
+ EXT DMA_Channel_TypeDef *DMA2_Channel4;
+#endif /*_DMA2_Channel4 */
+
+#ifdef _DMA2_Channel5
+ EXT DMA_Channel_TypeDef *DMA2_Channel5;
+#endif /*_DMA2_Channel5 */
+
+#ifdef _RCC
+ EXT RCC_TypeDef *RCC;
+#endif /*_RCC */
+
+#ifdef _CRC
+ EXT CRC_TypeDef *CRC;
+#endif /*_CRC */
+
+#ifdef _FLASH
+ EXT FLASH_TypeDef *FLASH;
+ EXT OB_TypeDef *OB;
+#endif /*_FLASH */
+
+#ifdef _FSMC
+ EXT FSMC_Bank1_TypeDef *FSMC_Bank1;
+ EXT FSMC_Bank1E_TypeDef *FSMC_Bank1E;
+ EXT FSMC_Bank2_TypeDef *FSMC_Bank2;
+ EXT FSMC_Bank3_TypeDef *FSMC_Bank3;
+ EXT FSMC_Bank4_TypeDef *FSMC_Bank4;
+#endif /*_FSMC */
+
+#ifdef _DBGMCU
+ EXT DBGMCU_TypeDef *DBGMCU;
+#endif /*_DBGMCU */
+
+#ifdef _SysTick
+ EXT SysTick_TypeDef *SysTick;
+#endif /*_SysTick */
+
+#ifdef _NVIC
+ EXT NVIC_TypeDef *NVIC;
+ EXT SCB_TypeDef *SCB;
+#endif /*_NVIC */
+
+#endif /* DEBUG */
+
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __STM32F10x_MAP_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_nvic.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_nvic.h new file mode 100755 index 0000000..be60c08 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_nvic.h @@ -0,0 +1,287 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_nvic.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* NVIC firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_NVIC_H
+#define __STM32F10x_NVIC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* NVIC Init Structure definition */
+typedef struct
+{
+ u8 NVIC_IRQChannel;
+ u8 NVIC_IRQChannelPreemptionPriority;
+ u8 NVIC_IRQChannelSubPriority;
+ FunctionalState NVIC_IRQChannelCmd;
+} NVIC_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+/* IRQ Channels --------------------------------------------------------------*/
+#define WWDG_IRQChannel ((u8)0x00) /* Window WatchDog Interrupt */
+#define PVD_IRQChannel ((u8)0x01) /* PVD through EXTI Line detection Interrupt */
+#define TAMPER_IRQChannel ((u8)0x02) /* Tamper Interrupt */
+#define RTC_IRQChannel ((u8)0x03) /* RTC global Interrupt */
+#define FLASH_IRQChannel ((u8)0x04) /* FLASH global Interrupt */
+#define RCC_IRQChannel ((u8)0x05) /* RCC global Interrupt */
+#define EXTI0_IRQChannel ((u8)0x06) /* EXTI Line0 Interrupt */
+#define EXTI1_IRQChannel ((u8)0x07) /* EXTI Line1 Interrupt */
+#define EXTI2_IRQChannel ((u8)0x08) /* EXTI Line2 Interrupt */
+#define EXTI3_IRQChannel ((u8)0x09) /* EXTI Line3 Interrupt */
+#define EXTI4_IRQChannel ((u8)0x0A) /* EXTI Line4 Interrupt */
+#define DMA1_Channel1_IRQChannel ((u8)0x0B) /* DMA1 Channel 1 global Interrupt */
+#define DMA1_Channel2_IRQChannel ((u8)0x0C) /* DMA1 Channel 2 global Interrupt */
+#define DMA1_Channel3_IRQChannel ((u8)0x0D) /* DMA1 Channel 3 global Interrupt */
+#define DMA1_Channel4_IRQChannel ((u8)0x0E) /* DMA1 Channel 4 global Interrupt */
+#define DMA1_Channel5_IRQChannel ((u8)0x0F) /* DMA1 Channel 5 global Interrupt */
+#define DMA1_Channel6_IRQChannel ((u8)0x10) /* DMA1 Channel 6 global Interrupt */
+#define DMA1_Channel7_IRQChannel ((u8)0x11) /* DMA1 Channel 7 global Interrupt */
+#define ADC1_2_IRQChannel ((u8)0x12) /* ADC1 et ADC2 global Interrupt */
+#define USB_HP_CAN_TX_IRQChannel ((u8)0x13) /* USB High Priority or CAN TX Interrupts */
+#define USB_LP_CAN_RX0_IRQChannel ((u8)0x14) /* USB Low Priority or CAN RX0 Interrupts */
+#define CAN_RX1_IRQChannel ((u8)0x15) /* CAN RX1 Interrupt */
+#define CAN_SCE_IRQChannel ((u8)0x16) /* CAN SCE Interrupt */
+#define EXTI9_5_IRQChannel ((u8)0x17) /* External Line[9:5] Interrupts */
+#define TIM1_BRK_IRQChannel ((u8)0x18) /* TIM1 Break Interrupt */
+#define TIM1_UP_IRQChannel ((u8)0x19) /* TIM1 Update Interrupt */
+#define TIM1_TRG_COM_IRQChannel ((u8)0x1A) /* TIM1 Trigger and Commutation Interrupt */
+#define TIM1_CC_IRQChannel ((u8)0x1B) /* TIM1 Capture Compare Interrupt */
+#define TIM2_IRQChannel ((u8)0x1C) /* TIM2 global Interrupt */
+#define TIM3_IRQChannel ((u8)0x1D) /* TIM3 global Interrupt */
+#define TIM4_IRQChannel ((u8)0x1E) /* TIM4 global Interrupt */
+#define I2C1_EV_IRQChannel ((u8)0x1F) /* I2C1 Event Interrupt */
+#define I2C1_ER_IRQChannel ((u8)0x20) /* I2C1 Error Interrupt */
+#define I2C2_EV_IRQChannel ((u8)0x21) /* I2C2 Event Interrupt */
+#define I2C2_ER_IRQChannel ((u8)0x22) /* I2C2 Error Interrupt */
+#define SPI1_IRQChannel ((u8)0x23) /* SPI1 global Interrupt */
+#define SPI2_IRQChannel ((u8)0x24) /* SPI2 global Interrupt */
+#define USART1_IRQChannel ((u8)0x25) /* USART1 global Interrupt */
+#define USART2_IRQChannel ((u8)0x26) /* USART2 global Interrupt */
+#define USART3_IRQChannel ((u8)0x27) /* USART3 global Interrupt */
+#define EXTI15_10_IRQChannel ((u8)0x28) /* External Line[15:10] Interrupts */
+#define RTCAlarm_IRQChannel ((u8)0x29) /* RTC Alarm through EXTI Line Interrupt */
+#define USBWakeUp_IRQChannel ((u8)0x2A) /* USB WakeUp from suspend through EXTI Line Interrupt */
+#define TIM8_BRK_IRQChannel ((u8)0x2B) /* TIM8 Break Interrupt */
+#define TIM8_UP_IRQChannel ((u8)0x2C) /* TIM8 Update Interrupt */
+#define TIM8_TRG_COM_IRQChannel ((u8)0x2D) /* TIM8 Trigger and Commutation Interrupt */
+#define TIM8_CC_IRQChannel ((u8)0x2E) /* TIM8 Capture Compare Interrupt */
+#define ADC3_IRQChannel ((u8)0x2F) /* ADC3 global Interrupt */
+#define FSMC_IRQChannel ((u8)0x30) /* FSMC global Interrupt */
+#define SDIO_IRQChannel ((u8)0x31) /* SDIO global Interrupt */
+#define TIM5_IRQChannel ((u8)0x32) /* TIM5 global Interrupt */
+#define SPI3_IRQChannel ((u8)0x33) /* SPI3 global Interrupt */
+#define UART4_IRQChannel ((u8)0x34) /* UART4 global Interrupt */
+#define UART5_IRQChannel ((u8)0x35) /* UART5 global Interrupt */
+#define TIM6_IRQChannel ((u8)0x36) /* TIM6 global Interrupt */
+#define TIM7_IRQChannel ((u8)0x37) /* TIM7 global Interrupt */
+#define DMA2_Channel1_IRQChannel ((u8)0x38) /* DMA2 Channel 1 global Interrupt */
+#define DMA2_Channel2_IRQChannel ((u8)0x39) /* DMA2 Channel 2 global Interrupt */
+#define DMA2_Channel3_IRQChannel ((u8)0x3A) /* DMA2 Channel 3 global Interrupt */
+#define DMA2_Channel4_5_IRQChannel ((u8)0x3B) /* DMA2 Channel 4 and DMA2 Channel 5 global Interrupt */
+
+
+#define IS_NVIC_IRQ_CHANNEL(CHANNEL) (((CHANNEL) == WWDG_IRQChannel) || \
+ ((CHANNEL) == PVD_IRQChannel) || \
+ ((CHANNEL) == TAMPER_IRQChannel) || \
+ ((CHANNEL) == RTC_IRQChannel) || \
+ ((CHANNEL) == FLASH_IRQChannel) || \
+ ((CHANNEL) == RCC_IRQChannel) || \
+ ((CHANNEL) == EXTI0_IRQChannel) || \
+ ((CHANNEL) == EXTI1_IRQChannel) || \
+ ((CHANNEL) == EXTI2_IRQChannel) || \
+ ((CHANNEL) == EXTI3_IRQChannel) || \
+ ((CHANNEL) == EXTI4_IRQChannel) || \
+ ((CHANNEL) == DMA1_Channel1_IRQChannel) || \
+ ((CHANNEL) == DMA1_Channel2_IRQChannel) || \
+ ((CHANNEL) == DMA1_Channel3_IRQChannel) || \
+ ((CHANNEL) == DMA1_Channel4_IRQChannel) || \
+ ((CHANNEL) == DMA1_Channel5_IRQChannel) || \
+ ((CHANNEL) == DMA1_Channel6_IRQChannel) || \
+ ((CHANNEL) == DMA1_Channel7_IRQChannel) || \
+ ((CHANNEL) == ADC1_2_IRQChannel) || \
+ ((CHANNEL) == USB_HP_CAN_TX_IRQChannel) || \
+ ((CHANNEL) == USB_LP_CAN_RX0_IRQChannel) || \
+ ((CHANNEL) == CAN_RX1_IRQChannel) || \
+ ((CHANNEL) == CAN_SCE_IRQChannel) || \
+ ((CHANNEL) == EXTI9_5_IRQChannel) || \
+ ((CHANNEL) == TIM1_BRK_IRQChannel) || \
+ ((CHANNEL) == TIM1_UP_IRQChannel) || \
+ ((CHANNEL) == TIM1_TRG_COM_IRQChannel) || \
+ ((CHANNEL) == TIM1_CC_IRQChannel) || \
+ ((CHANNEL) == TIM2_IRQChannel) || \
+ ((CHANNEL) == TIM3_IRQChannel) || \
+ ((CHANNEL) == TIM4_IRQChannel) || \
+ ((CHANNEL) == I2C1_EV_IRQChannel) || \
+ ((CHANNEL) == I2C1_ER_IRQChannel) || \
+ ((CHANNEL) == I2C2_EV_IRQChannel) || \
+ ((CHANNEL) == I2C2_ER_IRQChannel) || \
+ ((CHANNEL) == SPI1_IRQChannel) || \
+ ((CHANNEL) == SPI2_IRQChannel) || \
+ ((CHANNEL) == USART1_IRQChannel) || \
+ ((CHANNEL) == USART2_IRQChannel) || \
+ ((CHANNEL) == USART3_IRQChannel) || \
+ ((CHANNEL) == EXTI15_10_IRQChannel) || \
+ ((CHANNEL) == RTCAlarm_IRQChannel) || \
+ ((CHANNEL) == USBWakeUp_IRQChannel) || \
+ ((CHANNEL) == TIM8_BRK_IRQChannel) || \
+ ((CHANNEL) == TIM8_UP_IRQChannel) || \
+ ((CHANNEL) == TIM8_TRG_COM_IRQChannel) || \
+ ((CHANNEL) == TIM8_CC_IRQChannel) || \
+ ((CHANNEL) == ADC3_IRQChannel) || \
+ ((CHANNEL) == FSMC_IRQChannel) || \
+ ((CHANNEL) == SDIO_IRQChannel) || \
+ ((CHANNEL) == TIM5_IRQChannel) || \
+ ((CHANNEL) == SPI3_IRQChannel) || \
+ ((CHANNEL) == UART4_IRQChannel) || \
+ ((CHANNEL) == UART5_IRQChannel) || \
+ ((CHANNEL) == TIM6_IRQChannel) || \
+ ((CHANNEL) == TIM7_IRQChannel) || \
+ ((CHANNEL) == DMA2_Channel1_IRQChannel) || \
+ ((CHANNEL) == DMA2_Channel2_IRQChannel) || \
+ ((CHANNEL) == DMA2_Channel3_IRQChannel) || \
+ ((CHANNEL) == DMA2_Channel4_5_IRQChannel))
+
+
+/* System Handlers -----------------------------------------------------------*/
+#define SystemHandler_NMI ((u32)0x00001F) /* NMI Handler */
+#define SystemHandler_HardFault ((u32)0x000000) /* Hard Fault Handler */
+#define SystemHandler_MemoryManage ((u32)0x043430) /* Memory Manage Handler */
+#define SystemHandler_BusFault ((u32)0x547931) /* Bus Fault Handler */
+#define SystemHandler_UsageFault ((u32)0x24C232) /* Usage Fault Handler */
+#define SystemHandler_SVCall ((u32)0x01FF40) /* SVCall Handler */
+#define SystemHandler_DebugMonitor ((u32)0x0A0080) /* Debug Monitor Handler */
+#define SystemHandler_PSV ((u32)0x02829C) /* PSV Handler */
+#define SystemHandler_SysTick ((u32)0x02C39A) /* SysTick Handler */
+
+#define IS_CONFIG_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_MemoryManage) || \
+ ((HANDLER) == SystemHandler_BusFault) || \
+ ((HANDLER) == SystemHandler_UsageFault))
+
+#define IS_PRIORITY_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_MemoryManage) || \
+ ((HANDLER) == SystemHandler_BusFault) || \
+ ((HANDLER) == SystemHandler_UsageFault) || \
+ ((HANDLER) == SystemHandler_SVCall) || \
+ ((HANDLER) == SystemHandler_DebugMonitor) || \
+ ((HANDLER) == SystemHandler_PSV) || \
+ ((HANDLER) == SystemHandler_SysTick))
+
+#define IS_GET_PENDING_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_MemoryManage) || \
+ ((HANDLER) == SystemHandler_BusFault) || \
+ ((HANDLER) == SystemHandler_SVCall))
+
+#define IS_SET_PENDING_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_NMI) || \
+ ((HANDLER) == SystemHandler_PSV) || \
+ ((HANDLER) == SystemHandler_SysTick))
+
+#define IS_CLEAR_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_PSV) || \
+ ((HANDLER) == SystemHandler_SysTick))
+
+#define IS_GET_ACTIVE_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_MemoryManage) || \
+ ((HANDLER) == SystemHandler_BusFault) || \
+ ((HANDLER) == SystemHandler_UsageFault) || \
+ ((HANDLER) == SystemHandler_SVCall) || \
+ ((HANDLER) == SystemHandler_DebugMonitor) || \
+ ((HANDLER) == SystemHandler_PSV) || \
+ ((HANDLER) == SystemHandler_SysTick))
+
+#define IS_FAULT_SOURCE_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_HardFault) || \
+ ((HANDLER) == SystemHandler_MemoryManage) || \
+ ((HANDLER) == SystemHandler_BusFault) || \
+ ((HANDLER) == SystemHandler_UsageFault) || \
+ ((HANDLER) == SystemHandler_DebugMonitor))
+
+#define IS_FAULT_ADDRESS_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_MemoryManage) || \
+ ((HANDLER) == SystemHandler_BusFault))
+
+
+/* Vector Table Base ---------------------------------------------------------*/
+#define NVIC_VectTab_RAM ((u32)0x20000000)
+#define NVIC_VectTab_FLASH ((u32)0x08000000)
+
+#define IS_NVIC_VECTTAB(VECTTAB) (((VECTTAB) == NVIC_VectTab_RAM) || \
+ ((VECTTAB) == NVIC_VectTab_FLASH))
+
+/* System Low Power ----------------------------------------------------------*/
+#define NVIC_LP_SEVONPEND ((u8)0x10)
+#define NVIC_LP_SLEEPDEEP ((u8)0x04)
+#define NVIC_LP_SLEEPONEXIT ((u8)0x02)
+
+#define IS_NVIC_LP(LP) (((LP) == NVIC_LP_SEVONPEND) || \
+ ((LP) == NVIC_LP_SLEEPDEEP) || \
+ ((LP) == NVIC_LP_SLEEPONEXIT))
+
+/* Preemption Priority Group -------------------------------------------------*/
+#define NVIC_PriorityGroup_0 ((u32)0x700) /* 0 bits for pre-emption priority
+ 4 bits for subpriority */
+#define NVIC_PriorityGroup_1 ((u32)0x600) /* 1 bits for pre-emption priority
+ 3 bits for subpriority */
+#define NVIC_PriorityGroup_2 ((u32)0x500) /* 2 bits for pre-emption priority
+ 2 bits for subpriority */
+#define NVIC_PriorityGroup_3 ((u32)0x400) /* 3 bits for pre-emption priority
+ 1 bits for subpriority */
+#define NVIC_PriorityGroup_4 ((u32)0x300) /* 4 bits for pre-emption priority
+ 0 bits for subpriority */
+
+#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PriorityGroup_0) || \
+ ((GROUP) == NVIC_PriorityGroup_1) || \
+ ((GROUP) == NVIC_PriorityGroup_2) || \
+ ((GROUP) == NVIC_PriorityGroup_3) || \
+ ((GROUP) == NVIC_PriorityGroup_4))
+
+#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x10)
+#define IS_NVIC_SUB_PRIORITY(PRIORITY) ((PRIORITY) < 0x10)
+#define IS_NVIC_OFFSET(OFFSET) ((OFFSET) < 0x0007FFFF)
+#define IS_NVIC_BASE_PRI(PRI) ((PRI) < 0x10)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void NVIC_DeInit(void);
+void NVIC_SCBDeInit(void);
+void NVIC_PriorityGroupConfig(u32 NVIC_PriorityGroup);
+void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct);
+void NVIC_StructInit(NVIC_InitTypeDef* NVIC_InitStruct);
+void NVIC_SETPRIMASK(void);
+void NVIC_RESETPRIMASK(void);
+void NVIC_SETFAULTMASK(void);
+void NVIC_RESETFAULTMASK(void);
+void NVIC_BASEPRICONFIG(u32 NewPriority);
+u32 NVIC_GetBASEPRI(void);
+u16 NVIC_GetCurrentPendingIRQChannel(void);
+ITStatus NVIC_GetIRQChannelPendingBitStatus(u8 NVIC_IRQChannel);
+void NVIC_SetIRQChannelPendingBit(u8 NVIC_IRQChannel);
+void NVIC_ClearIRQChannelPendingBit(u8 NVIC_IRQChannel);
+u16 NVIC_GetCurrentActiveHandler(void);
+ITStatus NVIC_GetIRQChannelActiveBitStatus(u8 NVIC_IRQChannel);
+u32 NVIC_GetCPUID(void);
+void NVIC_SetVectorTable(u32 NVIC_VectTab, u32 Offset);
+void NVIC_GenerateSystemReset(void);
+void NVIC_GenerateCoreReset(void);
+void NVIC_SystemLPConfig(u8 LowPowerMode, FunctionalState NewState);
+void NVIC_SystemHandlerConfig(u32 SystemHandler, FunctionalState NewState);
+void NVIC_SystemHandlerPriorityConfig(u32 SystemHandler, u8 SystemHandlerPreemptionPriority,
+ u8 SystemHandlerSubPriority);
+ITStatus NVIC_GetSystemHandlerPendingBitStatus(u32 SystemHandler);
+void NVIC_SetSystemHandlerPendingBit(u32 SystemHandler);
+void NVIC_ClearSystemHandlerPendingBit(u32 SystemHandler);
+ITStatus NVIC_GetSystemHandlerActiveBitStatus(u32 SystemHandler);
+u32 NVIC_GetFaultHandlerSources(u32 SystemHandler);
+u32 NVIC_GetFaultAddress(u32 SystemHandler);
+
+#endif /* __STM32F10x_NVIC_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_pwr.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_pwr.h new file mode 100755 index 0000000..97b87c0 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_pwr.h @@ -0,0 +1,77 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_pwr.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* PWR firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_PWR_H
+#define __STM32F10x_PWR_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* PVD detection level */
+#define PWR_PVDLevel_2V2 ((u32)0x00000000)
+#define PWR_PVDLevel_2V3 ((u32)0x00000020)
+#define PWR_PVDLevel_2V4 ((u32)0x00000040)
+#define PWR_PVDLevel_2V5 ((u32)0x00000060)
+#define PWR_PVDLevel_2V6 ((u32)0x00000080)
+#define PWR_PVDLevel_2V7 ((u32)0x000000A0)
+#define PWR_PVDLevel_2V8 ((u32)0x000000C0)
+#define PWR_PVDLevel_2V9 ((u32)0x000000E0)
+
+#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLevel_2V2) || ((LEVEL) == PWR_PVDLevel_2V3)|| \
+ ((LEVEL) == PWR_PVDLevel_2V4) || ((LEVEL) == PWR_PVDLevel_2V5)|| \
+ ((LEVEL) == PWR_PVDLevel_2V6) || ((LEVEL) == PWR_PVDLevel_2V7)|| \
+ ((LEVEL) == PWR_PVDLevel_2V8) || ((LEVEL) == PWR_PVDLevel_2V9))
+
+/* Regulator state is STOP mode */
+#define PWR_Regulator_ON ((u32)0x00000000)
+#define PWR_Regulator_LowPower ((u32)0x00000001)
+
+#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_Regulator_ON) || \
+ ((REGULATOR) == PWR_Regulator_LowPower))
+
+/* STOP mode entry */
+#define PWR_STOPEntry_WFI ((u8)0x01)
+#define PWR_STOPEntry_WFE ((u8)0x02)
+
+#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPEntry_WFI) || ((ENTRY) == PWR_STOPEntry_WFE))
+
+/* PWR Flag */
+#define PWR_FLAG_WU ((u32)0x00000001)
+#define PWR_FLAG_SB ((u32)0x00000002)
+#define PWR_FLAG_PVDO ((u32)0x00000004)
+
+#define IS_PWR_GET_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB) || \
+ ((FLAG) == PWR_FLAG_PVDO))
+#define IS_PWR_CLEAR_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void PWR_DeInit(void);
+void PWR_BackupAccessCmd(FunctionalState NewState);
+void PWR_PVDCmd(FunctionalState NewState);
+void PWR_PVDLevelConfig(u32 PWR_PVDLevel);
+void PWR_WakeUpPinCmd(FunctionalState NewState);
+void PWR_EnterSTOPMode(u32 PWR_Regulator, u8 PWR_STOPEntry);
+void PWR_EnterSTANDBYMode(void);
+FlagStatus PWR_GetFlagStatus(u32 PWR_FLAG);
+void PWR_ClearFlag(u32 PWR_FLAG);
+
+#endif /* __STM32F10x_PWR_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_rcc.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_rcc.h new file mode 100755 index 0000000..703c3f7 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_rcc.h @@ -0,0 +1,288 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_rcc.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* RCC firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_RCC_H
+#define __STM32F10x_RCC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+typedef struct
+{
+ u32 SYSCLK_Frequency;
+ u32 HCLK_Frequency;
+ u32 PCLK1_Frequency;
+ u32 PCLK2_Frequency;
+ u32 ADCCLK_Frequency;
+}RCC_ClocksTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+/* HSE configuration */
+#define RCC_HSE_OFF ((u32)0x00000000)
+#define RCC_HSE_ON ((u32)0x00010000)
+#define RCC_HSE_Bypass ((u32)0x00040000)
+
+#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \
+ ((HSE) == RCC_HSE_Bypass))
+
+/* PLL entry clock source */
+#define RCC_PLLSource_HSI_Div2 ((u32)0x00000000)
+#define RCC_PLLSource_HSE_Div1 ((u32)0x00010000)
+#define RCC_PLLSource_HSE_Div2 ((u32)0x00030000)
+
+#define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \
+ ((SOURCE) == RCC_PLLSource_HSE_Div1) || \
+ ((SOURCE) == RCC_PLLSource_HSE_Div2))
+
+/* PLL multiplication factor */
+#define RCC_PLLMul_2 ((u32)0x00000000)
+#define RCC_PLLMul_3 ((u32)0x00040000)
+#define RCC_PLLMul_4 ((u32)0x00080000)
+#define RCC_PLLMul_5 ((u32)0x000C0000)
+#define RCC_PLLMul_6 ((u32)0x00100000)
+#define RCC_PLLMul_7 ((u32)0x00140000)
+#define RCC_PLLMul_8 ((u32)0x00180000)
+#define RCC_PLLMul_9 ((u32)0x001C0000)
+#define RCC_PLLMul_10 ((u32)0x00200000)
+#define RCC_PLLMul_11 ((u32)0x00240000)
+#define RCC_PLLMul_12 ((u32)0x00280000)
+#define RCC_PLLMul_13 ((u32)0x002C0000)
+#define RCC_PLLMul_14 ((u32)0x00300000)
+#define RCC_PLLMul_15 ((u32)0x00340000)
+#define RCC_PLLMul_16 ((u32)0x00380000)
+
+#define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_2) || ((MUL) == RCC_PLLMul_3) || \
+ ((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \
+ ((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \
+ ((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \
+ ((MUL) == RCC_PLLMul_10) || ((MUL) == RCC_PLLMul_11) || \
+ ((MUL) == RCC_PLLMul_12) || ((MUL) == RCC_PLLMul_13) || \
+ ((MUL) == RCC_PLLMul_14) || ((MUL) == RCC_PLLMul_15) || \
+ ((MUL) == RCC_PLLMul_16))
+
+/* System clock source */
+#define RCC_SYSCLKSource_HSI ((u32)0x00000000)
+#define RCC_SYSCLKSource_HSE ((u32)0x00000001)
+#define RCC_SYSCLKSource_PLLCLK ((u32)0x00000002)
+
+#define IS_RCC_SYSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSource_HSI) || \
+ ((SOURCE) == RCC_SYSCLKSource_HSE) || \
+ ((SOURCE) == RCC_SYSCLKSource_PLLCLK))
+
+/* AHB clock source */
+#define RCC_SYSCLK_Div1 ((u32)0x00000000)
+#define RCC_SYSCLK_Div2 ((u32)0x00000080)
+#define RCC_SYSCLK_Div4 ((u32)0x00000090)
+#define RCC_SYSCLK_Div8 ((u32)0x000000A0)
+#define RCC_SYSCLK_Div16 ((u32)0x000000B0)
+#define RCC_SYSCLK_Div64 ((u32)0x000000C0)
+#define RCC_SYSCLK_Div128 ((u32)0x000000D0)
+#define RCC_SYSCLK_Div256 ((u32)0x000000E0)
+#define RCC_SYSCLK_Div512 ((u32)0x000000F0)
+
+#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_Div1) || ((HCLK) == RCC_SYSCLK_Div2) || \
+ ((HCLK) == RCC_SYSCLK_Div4) || ((HCLK) == RCC_SYSCLK_Div8) || \
+ ((HCLK) == RCC_SYSCLK_Div16) || ((HCLK) == RCC_SYSCLK_Div64) || \
+ ((HCLK) == RCC_SYSCLK_Div128) || ((HCLK) == RCC_SYSCLK_Div256) || \
+ ((HCLK) == RCC_SYSCLK_Div512))
+
+/* APB1/APB2 clock source */
+#define RCC_HCLK_Div1 ((u32)0x00000000)
+#define RCC_HCLK_Div2 ((u32)0x00000400)
+#define RCC_HCLK_Div4 ((u32)0x00000500)
+#define RCC_HCLK_Div8 ((u32)0x00000600)
+#define RCC_HCLK_Div16 ((u32)0x00000700)
+
+#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_Div1) || ((PCLK) == RCC_HCLK_Div2) || \
+ ((PCLK) == RCC_HCLK_Div4) || ((PCLK) == RCC_HCLK_Div8) || \
+ ((PCLK) == RCC_HCLK_Div16))
+
+/* RCC Interrupt source */
+#define RCC_IT_LSIRDY ((u8)0x01)
+#define RCC_IT_LSERDY ((u8)0x02)
+#define RCC_IT_HSIRDY ((u8)0x04)
+#define RCC_IT_HSERDY ((u8)0x08)
+#define RCC_IT_PLLRDY ((u8)0x10)
+#define RCC_IT_CSS ((u8)0x80)
+
+#define IS_RCC_IT(IT) ((((IT) & (u8)0xE0) == 0x00) && ((IT) != 0x00))
+#define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \
+ ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \
+ ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS))
+#define IS_RCC_CLEAR_IT(IT) ((((IT) & (u8)0x60) == 0x00) && ((IT) != 0x00))
+
+/* USB clock source */
+#define RCC_USBCLKSource_PLLCLK_1Div5 ((u8)0x00)
+#define RCC_USBCLKSource_PLLCLK_Div1 ((u8)0x01)
+
+#define IS_RCC_USBCLK_SOURCE(SOURCE) (((SOURCE) == RCC_USBCLKSource_PLLCLK_1Div5) || \
+ ((SOURCE) == RCC_USBCLKSource_PLLCLK_Div1))
+
+/* ADC clock source */
+#define RCC_PCLK2_Div2 ((u32)0x00000000)
+#define RCC_PCLK2_Div4 ((u32)0x00004000)
+#define RCC_PCLK2_Div6 ((u32)0x00008000)
+#define RCC_PCLK2_Div8 ((u32)0x0000C000)
+
+#define IS_RCC_ADCCLK(ADCCLK) (((ADCCLK) == RCC_PCLK2_Div2) || ((ADCCLK) == RCC_PCLK2_Div4) || \
+ ((ADCCLK) == RCC_PCLK2_Div6) || ((ADCCLK) == RCC_PCLK2_Div8))
+
+/* LSE configuration */
+#define RCC_LSE_OFF ((u8)0x00)
+#define RCC_LSE_ON ((u8)0x01)
+#define RCC_LSE_Bypass ((u8)0x04)
+
+#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \
+ ((LSE) == RCC_LSE_Bypass))
+
+/* RTC clock source */
+#define RCC_RTCCLKSource_LSE ((u32)0x00000100)
+#define RCC_RTCCLKSource_LSI ((u32)0x00000200)
+#define RCC_RTCCLKSource_HSE_Div128 ((u32)0x00000300)
+
+#define IS_RCC_RTCCLK_SOURCE(SOURCE) (((SOURCE) == RCC_RTCCLKSource_LSE) || \
+ ((SOURCE) == RCC_RTCCLKSource_LSI) || \
+ ((SOURCE) == RCC_RTCCLKSource_HSE_Div128))
+
+/* AHB peripheral */
+#define RCC_AHBPeriph_DMA1 ((u32)0x00000001)
+#define RCC_AHBPeriph_DMA2 ((u32)0x00000002)
+#define RCC_AHBPeriph_SRAM ((u32)0x00000004)
+#define RCC_AHBPeriph_FLITF ((u32)0x00000010)
+#define RCC_AHBPeriph_CRC ((u32)0x00000040)
+#define RCC_AHBPeriph_FSMC ((u32)0x00000100)
+#define RCC_AHBPeriph_SDIO ((u32)0x00000400)
+
+#define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFAA8) == 0x00) && ((PERIPH) != 0x00))
+
+/* APB2 peripheral */
+#define RCC_APB2Periph_AFIO ((u32)0x00000001)
+#define RCC_APB2Periph_GPIOA ((u32)0x00000004)
+#define RCC_APB2Periph_GPIOB ((u32)0x00000008)
+#define RCC_APB2Periph_GPIOC ((u32)0x00000010)
+#define RCC_APB2Periph_GPIOD ((u32)0x00000020)
+#define RCC_APB2Periph_GPIOE ((u32)0x00000040)
+#define RCC_APB2Periph_GPIOF ((u32)0x00000080)
+#define RCC_APB2Periph_GPIOG ((u32)0x00000100)
+#define RCC_APB2Periph_ADC1 ((u32)0x00000200)
+#define RCC_APB2Periph_ADC2 ((u32)0x00000400)
+#define RCC_APB2Periph_TIM1 ((u32)0x00000800)
+#define RCC_APB2Periph_SPI1 ((u32)0x00001000)
+#define RCC_APB2Periph_TIM8 ((u32)0x00002000)
+#define RCC_APB2Periph_USART1 ((u32)0x00004000)
+#define RCC_APB2Periph_ADC3 ((u32)0x00008000)
+#define RCC_APB2Periph_ALL ((u32)0x0000FFFD)
+
+#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xFFFF0002) == 0x00) && ((PERIPH) != 0x00))
+
+/* APB1 peripheral */
+#define RCC_APB1Periph_TIM2 ((u32)0x00000001)
+#define RCC_APB1Periph_TIM3 ((u32)0x00000002)
+#define RCC_APB1Periph_TIM4 ((u32)0x00000004)
+#define RCC_APB1Periph_TIM5 ((u32)0x00000008)
+#define RCC_APB1Periph_TIM6 ((u32)0x00000010)
+#define RCC_APB1Periph_TIM7 ((u32)0x00000020)
+#define RCC_APB1Periph_WWDG ((u32)0x00000800)
+#define RCC_APB1Periph_SPI2 ((u32)0x00004000)
+#define RCC_APB1Periph_SPI3 ((u32)0x00008000)
+#define RCC_APB1Periph_USART2 ((u32)0x00020000)
+#define RCC_APB1Periph_USART3 ((u32)0x00040000)
+#define RCC_APB1Periph_UART4 ((u32)0x00080000)
+#define RCC_APB1Periph_UART5 ((u32)0x00100000)
+#define RCC_APB1Periph_I2C1 ((u32)0x00200000)
+#define RCC_APB1Periph_I2C2 ((u32)0x00400000)
+#define RCC_APB1Periph_USB ((u32)0x00800000)
+#define RCC_APB1Periph_CAN ((u32)0x02000000)
+#define RCC_APB1Periph_BKP ((u32)0x08000000)
+#define RCC_APB1Periph_PWR ((u32)0x10000000)
+#define RCC_APB1Periph_DAC ((u32)0x20000000)
+#define RCC_APB1Periph_ALL ((u32)0x3AFEC83F)
+
+#define IS_RCC_APB1_PERIPH(PERIPH) ((((PERIPH) & 0xC50137C0) == 0x00) && ((PERIPH) != 0x00))
+
+/* Clock source to output on MCO pin */
+#define RCC_MCO_NoClock ((u8)0x00)
+#define RCC_MCO_SYSCLK ((u8)0x04)
+#define RCC_MCO_HSI ((u8)0x05)
+#define RCC_MCO_HSE ((u8)0x06)
+#define RCC_MCO_PLLCLK_Div2 ((u8)0x07)
+
+#define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \
+ ((MCO) == RCC_MCO_SYSCLK) || ((MCO) == RCC_MCO_HSE) || \
+ ((MCO) == RCC_MCO_PLLCLK_Div2))
+
+/* RCC Flag */
+#define RCC_FLAG_HSIRDY ((u8)0x20)
+#define RCC_FLAG_HSERDY ((u8)0x31)
+#define RCC_FLAG_PLLRDY ((u8)0x39)
+#define RCC_FLAG_LSERDY ((u8)0x41)
+#define RCC_FLAG_LSIRDY ((u8)0x61)
+#define RCC_FLAG_PINRST ((u8)0x7A)
+#define RCC_FLAG_PORRST ((u8)0x7B)
+#define RCC_FLAG_SFTRST ((u8)0x7C)
+#define RCC_FLAG_IWDGRST ((u8)0x7D)
+#define RCC_FLAG_WWDGRST ((u8)0x7E)
+#define RCC_FLAG_LPWRRST ((u8)0x7F)
+
+#define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \
+ ((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \
+ ((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \
+ ((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \
+ ((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \
+ ((FLAG) == RCC_FLAG_LPWRRST))
+
+#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1F)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void RCC_DeInit(void);
+void RCC_HSEConfig(u32 RCC_HSE);
+ErrorStatus RCC_WaitForHSEStartUp(void);
+void RCC_AdjustHSICalibrationValue(u8 HSICalibrationValue);
+void RCC_HSICmd(FunctionalState NewState);
+void RCC_PLLConfig(u32 RCC_PLLSource, u32 RCC_PLLMul);
+void RCC_PLLCmd(FunctionalState NewState);
+void RCC_SYSCLKConfig(u32 RCC_SYSCLKSource);
+u8 RCC_GetSYSCLKSource(void);
+void RCC_HCLKConfig(u32 RCC_SYSCLK);
+void RCC_PCLK1Config(u32 RCC_HCLK);
+void RCC_PCLK2Config(u32 RCC_HCLK);
+void RCC_ITConfig(u8 RCC_IT, FunctionalState NewState);
+void RCC_USBCLKConfig(u32 RCC_USBCLKSource);
+void RCC_ADCCLKConfig(u32 RCC_PCLK2);
+void RCC_LSEConfig(u8 RCC_LSE);
+void RCC_LSICmd(FunctionalState NewState);
+void RCC_RTCCLKConfig(u32 RCC_RTCCLKSource);
+void RCC_RTCCLKCmd(FunctionalState NewState);
+void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks);
+void RCC_AHBPeriphClockCmd(u32 RCC_AHBPeriph, FunctionalState NewState);
+void RCC_APB2PeriphClockCmd(u32 RCC_APB2Periph, FunctionalState NewState);
+void RCC_APB1PeriphClockCmd(u32 RCC_APB1Periph, FunctionalState NewState);
+void RCC_APB2PeriphResetCmd(u32 RCC_APB2Periph, FunctionalState NewState);
+void RCC_APB1PeriphResetCmd(u32 RCC_APB1Periph, FunctionalState NewState);
+void RCC_BackupResetCmd(FunctionalState NewState);
+void RCC_ClockSecuritySystemCmd(FunctionalState NewState);
+void RCC_MCOConfig(u8 RCC_MCO);
+FlagStatus RCC_GetFlagStatus(u8 RCC_FLAG);
+void RCC_ClearFlag(void);
+ITStatus RCC_GetITStatus(u8 RCC_IT);
+void RCC_ClearITPendingBit(u8 RCC_IT);
+
+#endif /* __STM32F10x_RCC_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_rtc.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_rtc.h new file mode 100755 index 0000000..843904c --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_rtc.h @@ -0,0 +1,70 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_rtc.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* RTC firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_RTC_H
+#define __STM32F10x_RTC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* RTC interrupts define -----------------------------------------------------*/
+#define RTC_IT_OW ((u16)0x0004) /* Overflow interrupt */
+#define RTC_IT_ALR ((u16)0x0002) /* Alarm interrupt */
+#define RTC_IT_SEC ((u16)0x0001) /* Second interrupt */
+
+#define IS_RTC_IT(IT) ((((IT) & (u16)0xFFF8) == 0x00) && ((IT) != 0x00))
+
+#define IS_RTC_GET_IT(IT) (((IT) == RTC_IT_OW) || ((IT) == RTC_IT_ALR) || \
+ ((IT) == RTC_IT_SEC))
+
+/* RTC interrupts flags ------------------------------------------------------*/
+#define RTC_FLAG_RTOFF ((u16)0x0020) /* RTC Operation OFF flag */
+#define RTC_FLAG_RSF ((u16)0x0008) /* Registers Synchronized flag */
+#define RTC_FLAG_OW ((u16)0x0004) /* Overflow flag */
+#define RTC_FLAG_ALR ((u16)0x0002) /* Alarm flag */
+#define RTC_FLAG_SEC ((u16)0x0001) /* Second flag */
+
+#define IS_RTC_CLEAR_FLAG(FLAG) ((((FLAG) & (u16)0xFFF0) == 0x00) && ((FLAG) != 0x00))
+
+#define IS_RTC_GET_FLAG(FLAG) (((FLAG) == RTC_FLAG_RTOFF) || ((FLAG) == RTC_FLAG_RSF) || \
+ ((FLAG) == RTC_FLAG_OW) || ((FLAG) == RTC_FLAG_ALR) || \
+ ((FLAG) == RTC_FLAG_SEC))
+
+#define IS_RTC_PRESCALER(PRESCALER) ((PRESCALER) <= 0xFFFFF)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void RTC_ITConfig(u16 RTC_IT, FunctionalState NewState);
+void RTC_EnterConfigMode(void);
+void RTC_ExitConfigMode(void);
+u32 RTC_GetCounter(void);
+void RTC_SetCounter(u32 CounterValue);
+void RTC_SetPrescaler(u32 PrescalerValue);
+void RTC_SetAlarm(u32 AlarmValue);
+u32 RTC_GetDivider(void);
+void RTC_WaitForLastTask(void);
+void RTC_WaitForSynchro(void);
+FlagStatus RTC_GetFlagStatus(u16 RTC_FLAG);
+void RTC_ClearFlag(u16 RTC_FLAG);
+ITStatus RTC_GetITStatus(u16 RTC_IT);
+void RTC_ClearITPendingBit(u16 RTC_IT);
+
+#endif /* __STM32F10x_RTC_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_sdio.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_sdio.h new file mode 100755 index 0000000..289c890 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_sdio.h @@ -0,0 +1,337 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_sdio.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* SDIO firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_SDIO_H
+#define __STM32F10x_SDIO_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+typedef struct
+{
+ u8 SDIO_ClockDiv;
+ u32 SDIO_ClockEdge;
+ u32 SDIO_ClockBypass;
+ u32 SDIO_ClockPowerSave;
+ u32 SDIO_BusWide;
+ u32 SDIO_HardwareFlowControl;
+} SDIO_InitTypeDef;
+
+typedef struct
+{
+ u32 SDIO_Argument;
+ u32 SDIO_CmdIndex;
+ u32 SDIO_Response;
+ u32 SDIO_Wait;
+ u32 SDIO_CPSM;
+} SDIO_CmdInitTypeDef;
+
+typedef struct
+{
+ u32 SDIO_DataTimeOut;
+ u32 SDIO_DataLength;
+ u32 SDIO_DataBlockSize;
+ u32 SDIO_TransferDir;
+ u32 SDIO_TransferMode;
+ u32 SDIO_DPSM;
+} SDIO_DataInitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+/* SDIO Clock Edge -----------------------------------------------------------*/
+#define SDIO_ClockEdge_Rising ((u32)0x00000000)
+#define SDIO_ClockEdge_Falling ((u32)0x00002000)
+
+#define IS_SDIO_CLOCK_EDGE(EDGE) (((EDGE) == SDIO_ClockEdge_Rising) || \
+ ((EDGE) == SDIO_ClockEdge_Falling))
+/* SDIO Clock Bypass ----------------------------------------------------------*/
+#define SDIO_ClockBypass_Disable ((u32)0x00000000)
+#define SDIO_ClockBypass_Enable ((u32)0x00000400)
+
+#define IS_SDIO_CLOCK_BYPASS(BYPASS) (((BYPASS) == SDIO_ClockBypass_Disable) || \
+ ((BYPASS) == SDIO_ClockBypass_Enable))
+
+/* SDIO Clock Power Save ----------------------------------------------------*/
+#define SDIO_ClockPowerSave_Disable ((u32)0x00000000)
+#define SDIO_ClockPowerSave_Enable ((u32)0x00000200)
+
+#define IS_SDIO_CLOCK_POWER_SAVE(SAVE) (((SAVE) == SDIO_ClockPowerSave_Disable) || \
+ ((SAVE) == SDIO_ClockPowerSave_Enable))
+
+/* SDIO Bus Wide -------------------------------------------------------------*/
+#define SDIO_BusWide_1b ((u32)0x00000000)
+#define SDIO_BusWide_4b ((u32)0x00000800)
+#define SDIO_BusWide_8b ((u32)0x00001000)
+
+#define IS_SDIO_BUS_WIDE(WIDE) (((WIDE) == SDIO_BusWide_1b) || ((WIDE) == SDIO_BusWide_4b) || \
+ ((WIDE) == SDIO_BusWide_8b))
+
+/* SDIO Hardware Flow Control -----------------------------------------------*/
+#define SDIO_HardwareFlowControl_Disable ((u32)0x00000000)
+#define SDIO_HardwareFlowControl_Enable ((u32)0x00004000)
+
+#define IS_SDIO_HARDWARE_FLOW_CONTROL(CONTROL) (((CONTROL) == SDIO_HardwareFlowControl_Disable) || \
+ ((CONTROL) == SDIO_HardwareFlowControl_Enable))
+
+/* SDIO Power State ----------------------------------------------------------*/
+#define SDIO_PowerState_OFF ((u32)0x00000000)
+#define SDIO_PowerState_ON ((u32)0x00000003)
+
+#define IS_SDIO_POWER_STATE(STATE) (((STATE) == SDIO_PowerState_OFF) || ((STATE) == SDIO_PowerState_ON))
+
+/* SDIO Interrupt soucres ----------------------------------------------------*/
+#define SDIO_IT_CCRCFAIL ((u32)0x00000001)
+#define SDIO_IT_DCRCFAIL ((u32)0x00000002)
+#define SDIO_IT_CTIMEOUT ((u32)0x00000004)
+#define SDIO_IT_DTIMEOUT ((u32)0x00000008)
+#define SDIO_IT_TXUNDERR ((u32)0x00000010)
+#define SDIO_IT_RXOVERR ((u32)0x00000020)
+#define SDIO_IT_CMDREND ((u32)0x00000040)
+#define SDIO_IT_CMDSENT ((u32)0x00000080)
+#define SDIO_IT_DATAEND ((u32)0x00000100)
+#define SDIO_IT_STBITERR ((u32)0x00000200)
+#define SDIO_IT_DBCKEND ((u32)0x00000400)
+#define SDIO_IT_CMDACT ((u32)0x00000800)
+#define SDIO_IT_TXACT ((u32)0x00001000)
+#define SDIO_IT_RXACT ((u32)0x00002000)
+#define SDIO_IT_TXFIFOHE ((u32)0x00004000)
+#define SDIO_IT_RXFIFOHF ((u32)0x00008000)
+#define SDIO_IT_TXFIFOF ((u32)0x00010000)
+#define SDIO_IT_RXFIFOF ((u32)0x00020000)
+#define SDIO_IT_TXFIFOE ((u32)0x00040000)
+#define SDIO_IT_RXFIFOE ((u32)0x00080000)
+#define SDIO_IT_TXDAVL ((u32)0x00100000)
+#define SDIO_IT_RXDAVL ((u32)0x00200000)
+#define SDIO_IT_SDIOIT ((u32)0x00400000)
+#define SDIO_IT_CEATAEND ((u32)0x00800000)
+
+#define IS_SDIO_IT(IT) ((((IT) & (u32)0xFF000000) == 0x00) && ((IT) != (u32)0x00))
+
+/* SDIO Command Index -------------------------------------------------------*/
+#define IS_SDIO_CMD_INDEX(INDEX) ((INDEX) < 0x40)
+
+/* SDIO Response Type --------------------------------------------------------*/
+#define SDIO_Response_No ((u32)0x00000000)
+#define SDIO_Response_Short ((u32)0x00000040)
+#define SDIO_Response_Long ((u32)0x000000C0)
+
+#define IS_SDIO_RESPONSE(RESPONSE) (((RESPONSE) == SDIO_Response_No) || \
+ ((RESPONSE) == SDIO_Response_Short) || \
+ ((RESPONSE) == SDIO_Response_Long))
+
+/* SDIO Wait Interrupt State -------------------------------------------------*/
+#define SDIO_Wait_No ((u32)0x00000000) /* SDIO No Wait, TimeOut is enabled */
+#define SDIO_Wait_IT ((u32)0x00000100) /* SDIO Wait Interrupt Request */
+#define SDIO_Wait_Pend ((u32)0x00000200) /* SDIO Wait End of transfer */
+
+#define IS_SDIO_WAIT(WAIT) (((WAIT) == SDIO_Wait_No) || ((WAIT) == SDIO_Wait_IT) || \
+ ((WAIT) == SDIO_Wait_Pend))
+
+/* SDIO CPSM State -----------------------------------------------------------*/
+#define SDIO_CPSM_Disable ((u32)0x00000000)
+#define SDIO_CPSM_Enable ((u32)0x00000400)
+
+#define IS_SDIO_CPSM(CPSM) (((CPSM) == SDIO_CPSM_Enable) || ((CPSM) == SDIO_CPSM_Disable))
+
+/* SDIO Response Registers ---------------------------------------------------*/
+#define SDIO_RESP1 ((u32)0x00000000)
+#define SDIO_RESP2 ((u32)0x00000004)
+#define SDIO_RESP3 ((u32)0x00000008)
+#define SDIO_RESP4 ((u32)0x0000000C)
+
+#define IS_SDIO_RESP(RESP) (((RESP) == SDIO_RESP1) || ((RESP) == SDIO_RESP2) || \
+ ((RESP) == SDIO_RESP3) || ((RESP) == SDIO_RESP4))
+
+/* SDIO Data Length ----------------------------------------------------------*/
+#define IS_SDIO_DATA_LENGTH(LENGTH) ((LENGTH) <= 0x01FFFFFF)
+
+/* SDIO Data Block Size ------------------------------------------------------*/
+#define SDIO_DataBlockSize_1b ((u32)0x00000000)
+#define SDIO_DataBlockSize_2b ((u32)0x00000010)
+#define SDIO_DataBlockSize_4b ((u32)0x00000020)
+#define SDIO_DataBlockSize_8b ((u32)0x00000030)
+#define SDIO_DataBlockSize_16b ((u32)0x00000040)
+#define SDIO_DataBlockSize_32b ((u32)0x00000050)
+#define SDIO_DataBlockSize_64b ((u32)0x00000060)
+#define SDIO_DataBlockSize_128b ((u32)0x00000070)
+#define SDIO_DataBlockSize_256b ((u32)0x00000080)
+#define SDIO_DataBlockSize_512b ((u32)0x00000090)
+#define SDIO_DataBlockSize_1024b ((u32)0x000000A0)
+#define SDIO_DataBlockSize_2048b ((u32)0x000000B0)
+#define SDIO_DataBlockSize_4096b ((u32)0x000000C0)
+#define SDIO_DataBlockSize_8192b ((u32)0x000000D0)
+#define SDIO_DataBlockSize_16384b ((u32)0x000000E0)
+
+#define IS_SDIO_BLOCK_SIZE(SIZE) (((SIZE) == SDIO_DataBlockSize_1b) || \
+ ((SIZE) == SDIO_DataBlockSize_2b) || \
+ ((SIZE) == SDIO_DataBlockSize_4b) || \
+ ((SIZE) == SDIO_DataBlockSize_8b) || \
+ ((SIZE) == SDIO_DataBlockSize_16b) || \
+ ((SIZE) == SDIO_DataBlockSize_32b) || \
+ ((SIZE) == SDIO_DataBlockSize_64b) || \
+ ((SIZE) == SDIO_DataBlockSize_128b) || \
+ ((SIZE) == SDIO_DataBlockSize_256b) || \
+ ((SIZE) == SDIO_DataBlockSize_512b) || \
+ ((SIZE) == SDIO_DataBlockSize_1024b) || \
+ ((SIZE) == SDIO_DataBlockSize_2048b) || \
+ ((SIZE) == SDIO_DataBlockSize_4096b) || \
+ ((SIZE) == SDIO_DataBlockSize_8192b) || \
+ ((SIZE) == SDIO_DataBlockSize_16384b))
+
+/* SDIO Transfer Direction ---------------------------------------------------*/
+#define SDIO_TransferDir_ToCard ((u32)0x00000000)
+#define SDIO_TransferDir_ToSDIO ((u32)0x00000002)
+
+#define IS_SDIO_TRANSFER_DIR(DIR) (((DIR) == SDIO_TransferDir_ToCard) || \
+ ((DIR) == SDIO_TransferDir_ToSDIO))
+
+/* SDIO Transfer Type --------------------------------------------------------*/
+#define SDIO_TransferMode_Block ((u32)0x00000000)
+#define SDIO_TransferMode_Stream ((u32)0x00000004)
+
+#define IS_SDIO_TRANSFER_MODE(MODE) (((MODE) == SDIO_TransferMode_Stream) || \
+ ((MODE) == SDIO_TransferMode_Block))
+
+/* SDIO DPSM State -----------------------------------------------------------*/
+#define SDIO_DPSM_Disable ((u32)0x00000000)
+#define SDIO_DPSM_Enable ((u32)0x00000001)
+
+#define IS_SDIO_DPSM(DPSM) (((DPSM) == SDIO_DPSM_Enable) || ((DPSM) == SDIO_DPSM_Disable))
+
+/* SDIO Flags ----------------------------------------------------------------*/
+#define SDIO_FLAG_CCRCFAIL ((u32)0x00000001)
+#define SDIO_FLAG_DCRCFAIL ((u32)0x00000002)
+#define SDIO_FLAG_CTIMEOUT ((u32)0x00000004)
+#define SDIO_FLAG_DTIMEOUT ((u32)0x00000008)
+#define SDIO_FLAG_TXUNDERR ((u32)0x00000010)
+#define SDIO_FLAG_RXOVERR ((u32)0x00000020)
+#define SDIO_FLAG_CMDREND ((u32)0x00000040)
+#define SDIO_FLAG_CMDSENT ((u32)0x00000080)
+#define SDIO_FLAG_DATAEND ((u32)0x00000100)
+#define SDIO_FLAG_STBITERR ((u32)0x00000200)
+#define SDIO_FLAG_DBCKEND ((u32)0x00000400)
+#define SDIO_FLAG_CMDACT ((u32)0x00000800)
+#define SDIO_FLAG_TXACT ((u32)0x00001000)
+#define SDIO_FLAG_RXACT ((u32)0x00002000)
+#define SDIO_FLAG_TXFIFOHE ((u32)0x00004000)
+#define SDIO_FLAG_RXFIFOHF ((u32)0x00008000)
+#define SDIO_FLAG_TXFIFOF ((u32)0x00010000)
+#define SDIO_FLAG_RXFIFOF ((u32)0x00020000)
+#define SDIO_FLAG_TXFIFOE ((u32)0x00040000)
+#define SDIO_FLAG_RXFIFOE ((u32)0x00080000)
+#define SDIO_FLAG_TXDAVL ((u32)0x00100000)
+#define SDIO_FLAG_RXDAVL ((u32)0x00200000)
+#define SDIO_FLAG_SDIOIT ((u32)0x00400000)
+#define SDIO_FLAG_CEATAEND ((u32)0x00800000)
+
+#define IS_SDIO_FLAG(FLAG) (((FLAG) == SDIO_FLAG_CCRCFAIL) || \
+ ((FLAG) == SDIO_FLAG_DCRCFAIL) || \
+ ((FLAG) == SDIO_FLAG_CTIMEOUT) || \
+ ((FLAG) == SDIO_FLAG_DTIMEOUT) || \
+ ((FLAG) == SDIO_FLAG_TXUNDERR) || \
+ ((FLAG) == SDIO_FLAG_RXOVERR) || \
+ ((FLAG) == SDIO_FLAG_CMDREND) || \
+ ((FLAG) == SDIO_FLAG_CMDSENT) || \
+ ((FLAG) == SDIO_FLAG_DATAEND) || \
+ ((FLAG) == SDIO_FLAG_STBITERR) || \
+ ((FLAG) == SDIO_FLAG_DBCKEND) || \
+ ((FLAG) == SDIO_FLAG_CMDACT) || \
+ ((FLAG) == SDIO_FLAG_TXACT) || \
+ ((FLAG) == SDIO_FLAG_RXACT) || \
+ ((FLAG) == SDIO_FLAG_TXFIFOHE) || \
+ ((FLAG) == SDIO_FLAG_RXFIFOHF) || \
+ ((FLAG) == SDIO_FLAG_TXFIFOF) || \
+ ((FLAG) == SDIO_FLAG_RXFIFOF) || \
+ ((FLAG) == SDIO_FLAG_TXFIFOE) || \
+ ((FLAG) == SDIO_FLAG_RXFIFOE) || \
+ ((FLAG) == SDIO_FLAG_TXDAVL) || \
+ ((FLAG) == SDIO_FLAG_RXDAVL) || \
+ ((FLAG) == SDIO_FLAG_SDIOIT) || \
+ ((FLAG) == SDIO_FLAG_CEATAEND))
+
+#define IS_SDIO_CLEAR_FLAG(FLAG) ((((FLAG) & (u32)0xFF3FF800) == 0x00) && ((FLAG) != (u32)0x00))
+
+#define IS_SDIO_GET_IT(IT) (((IT) == SDIO_IT_CCRCFAIL) || \
+ ((IT) == SDIO_IT_DCRCFAIL) || \
+ ((IT) == SDIO_IT_CTIMEOUT) || \
+ ((IT) == SDIO_IT_DTIMEOUT) || \
+ ((IT) == SDIO_IT_TXUNDERR) || \
+ ((IT) == SDIO_IT_RXOVERR) || \
+ ((IT) == SDIO_IT_CMDREND) || \
+ ((IT) == SDIO_IT_CMDSENT) || \
+ ((IT) == SDIO_IT_DATAEND) || \
+ ((IT) == SDIO_IT_STBITERR) || \
+ ((IT) == SDIO_IT_DBCKEND) || \
+ ((IT) == SDIO_IT_CMDACT) || \
+ ((IT) == SDIO_IT_TXACT) || \
+ ((IT) == SDIO_IT_RXACT) || \
+ ((IT) == SDIO_IT_TXFIFOHE) || \
+ ((IT) == SDIO_IT_RXFIFOHF) || \
+ ((IT) == SDIO_IT_TXFIFOF) || \
+ ((IT) == SDIO_IT_RXFIFOF) || \
+ ((IT) == SDIO_IT_TXFIFOE) || \
+ ((IT) == SDIO_IT_RXFIFOE) || \
+ ((IT) == SDIO_IT_TXDAVL) || \
+ ((IT) == SDIO_IT_RXDAVL) || \
+ ((IT) == SDIO_IT_SDIOIT) || \
+ ((IT) == SDIO_IT_CEATAEND))
+
+#define IS_SDIO_CLEAR_IT(IT) ((((IT) & (u32)0xFF3FF800) == 0x00) && ((IT) != (u32)0x00))
+
+/* SDIO Read Wait Mode -------------------------------------------------------*/
+#define SDIO_ReadWaitMode_CLK ((u32)0x00000000)
+#define SDIO_ReadWaitMode_DATA2 ((u32)0x00000001)
+
+#define IS_SDIO_READWAIT_MODE(MODE) (((MODE) == SDIO_ReadWaitMode_CLK) || \
+ ((MODE) == SDIO_ReadWaitMode_DATA2))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void SDIO_DeInit(void);
+void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct);
+void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct);
+void SDIO_ClockCmd(FunctionalState NewState);
+void SDIO_SetPowerState(u32 SDIO_PowerState);
+u32 SDIO_GetPowerState(void);
+void SDIO_ITConfig(u32 SDIO_IT, FunctionalState NewState);
+void SDIO_DMACmd(FunctionalState NewState);
+void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct);
+void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct);
+u8 SDIO_GetCommandResponse(void);
+u32 SDIO_GetResponse(u32 SDIO_RESP);
+void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct);
+void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct);
+u32 SDIO_GetDataCounter(void);
+u32 SDIO_ReadData(void);
+void SDIO_WriteData(u32 Data);
+u32 SDIO_GetFIFOCount(void);
+void SDIO_StartSDIOReadWait(FunctionalState NewState);
+void SDIO_StopSDIOReadWait(FunctionalState NewState);
+void SDIO_SetSDIOReadWaitMode(u32 SDIO_ReadWaitMode);
+void SDIO_SetSDIOOperation(FunctionalState NewState);
+void SDIO_SendSDIOSuspendCmd(FunctionalState NewState);
+void SDIO_CommandCompletionCmd(FunctionalState NewState);
+void SDIO_CEATAITCmd(FunctionalState NewState);
+void SDIO_SendCEATACmd(FunctionalState NewState);
+FlagStatus SDIO_GetFlagStatus(u32 SDIO_FLAG);
+void SDIO_ClearFlag(u32 SDIO_FLAG);
+ITStatus SDIO_GetITStatus(u32 SDIO_IT);
+void SDIO_ClearITPendingBit(u32 SDIO_IT);
+
+#endif /* __STM32F10x_SDIO_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_spi.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_spi.h new file mode 100755 index 0000000..e563132 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_spi.h @@ -0,0 +1,292 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_spi.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* SPI firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_SPI_H
+#define __STM32F10x_SPI_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* SPI Init structure definition */
+typedef struct
+{
+ u16 SPI_Direction;
+ u16 SPI_Mode;
+ u16 SPI_DataSize;
+ u16 SPI_CPOL;
+ u16 SPI_CPHA;
+ u16 SPI_NSS;
+ u16 SPI_BaudRatePrescaler;
+ u16 SPI_FirstBit;
+ u16 SPI_CRCPolynomial;
+}SPI_InitTypeDef;
+
+/* I2S Init structure definition */
+typedef struct
+{
+ u16 I2S_Mode;
+ u16 I2S_Standard;
+ u16 I2S_DataFormat;
+ u16 I2S_MCLKOutput;
+ u16 I2S_AudioFreq;
+ u16 I2S_CPOL;
+}I2S_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+#define IS_SPI_ALL_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == SPI1_BASE) || \
+ ((*(u32*)&(PERIPH)) == SPI2_BASE) || \
+ ((*(u32*)&(PERIPH)) == SPI3_BASE))
+
+#define IS_SPI_23_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == SPI2_BASE) || \
+ ((*(u32*)&(PERIPH)) == SPI3_BASE))
+
+/* SPI data direction mode */
+#define SPI_Direction_2Lines_FullDuplex ((u16)0x0000)
+#define SPI_Direction_2Lines_RxOnly ((u16)0x0400)
+#define SPI_Direction_1Line_Rx ((u16)0x8000)
+#define SPI_Direction_1Line_Tx ((u16)0xC000)
+
+#define IS_SPI_DIRECTION_MODE(MODE) (((MODE) == SPI_Direction_2Lines_FullDuplex) || \
+ ((MODE) == SPI_Direction_2Lines_RxOnly) || \
+ ((MODE) == SPI_Direction_1Line_Rx) || \
+ ((MODE) == SPI_Direction_1Line_Tx))
+
+/* SPI master/slave mode */
+#define SPI_Mode_Master ((u16)0x0104)
+#define SPI_Mode_Slave ((u16)0x0000)
+
+#define IS_SPI_MODE(MODE) (((MODE) == SPI_Mode_Master) || \
+ ((MODE) == SPI_Mode_Slave))
+
+/* SPI data size */
+#define SPI_DataSize_16b ((u16)0x0800)
+#define SPI_DataSize_8b ((u16)0x0000)
+
+#define IS_SPI_DATASIZE(DATASIZE) (((DATASIZE) == SPI_DataSize_16b) || \
+ ((DATASIZE) == SPI_DataSize_8b))
+
+/* SPI Clock Polarity */
+#define SPI_CPOL_Low ((u16)0x0000)
+#define SPI_CPOL_High ((u16)0x0002)
+
+#define IS_SPI_CPOL(CPOL) (((CPOL) == SPI_CPOL_Low) || \
+ ((CPOL) == SPI_CPOL_High))
+
+/* SPI Clock Phase */
+#define SPI_CPHA_1Edge ((u16)0x0000)
+#define SPI_CPHA_2Edge ((u16)0x0001)
+
+#define IS_SPI_CPHA(CPHA) (((CPHA) == SPI_CPHA_1Edge) || \
+ ((CPHA) == SPI_CPHA_2Edge))
+
+/* SPI Slave Select management */
+#define SPI_NSS_Soft ((u16)0x0200)
+#define SPI_NSS_Hard ((u16)0x0000)
+
+#define IS_SPI_NSS(NSS) (((NSS) == SPI_NSS_Soft) || \
+ ((NSS) == SPI_NSS_Hard))
+
+/* SPI BaudRate Prescaler */
+#define SPI_BaudRatePrescaler_2 ((u16)0x0000)
+#define SPI_BaudRatePrescaler_4 ((u16)0x0008)
+#define SPI_BaudRatePrescaler_8 ((u16)0x0010)
+#define SPI_BaudRatePrescaler_16 ((u16)0x0018)
+#define SPI_BaudRatePrescaler_32 ((u16)0x0020)
+#define SPI_BaudRatePrescaler_64 ((u16)0x0028)
+#define SPI_BaudRatePrescaler_128 ((u16)0x0030)
+#define SPI_BaudRatePrescaler_256 ((u16)0x0038)
+
+#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER) (((PRESCALER) == SPI_BaudRatePrescaler_2) || \
+ ((PRESCALER) == SPI_BaudRatePrescaler_4) || \
+ ((PRESCALER) == SPI_BaudRatePrescaler_8) || \
+ ((PRESCALER) == SPI_BaudRatePrescaler_16) || \
+ ((PRESCALER) == SPI_BaudRatePrescaler_32) || \
+ ((PRESCALER) == SPI_BaudRatePrescaler_64) || \
+ ((PRESCALER) == SPI_BaudRatePrescaler_128) || \
+ ((PRESCALER) == SPI_BaudRatePrescaler_256))
+
+/* SPI MSB/LSB transmission */
+#define SPI_FirstBit_MSB ((u16)0x0000)
+#define SPI_FirstBit_LSB ((u16)0x0080)
+
+#define IS_SPI_FIRST_BIT(BIT) (((BIT) == SPI_FirstBit_MSB) || \
+ ((BIT) == SPI_FirstBit_LSB))
+
+/* I2S Mode */
+#define I2S_Mode_SlaveTx ((u16)0x0000)
+#define I2S_Mode_SlaveRx ((u16)0x0100)
+#define I2S_Mode_MasterTx ((u16)0x0200)
+#define I2S_Mode_MasterRx ((u16)0x0300)
+
+#define IS_I2S_MODE(MODE) (((MODE) == I2S_Mode_SlaveTx) || \
+ ((MODE) == I2S_Mode_SlaveRx) || \
+ ((MODE) == I2S_Mode_MasterTx) || \
+ ((MODE) == I2S_Mode_MasterRx) )
+
+/* I2S Standard */
+#define I2S_Standard_Phillips ((u16)0x0000)
+#define I2S_Standard_MSB ((u16)0x0010)
+#define I2S_Standard_LSB ((u16)0x0020)
+#define I2S_Standard_PCMShort ((u16)0x0030)
+#define I2S_Standard_PCMLong ((u16)0x00B0)
+
+#define IS_I2S_STANDARD(STANDARD) (((STANDARD) == I2S_Standard_Phillips) || \
+ ((STANDARD) == I2S_Standard_MSB) || \
+ ((STANDARD) == I2S_Standard_LSB) || \
+ ((STANDARD) == I2S_Standard_PCMShort) || \
+ ((STANDARD) == I2S_Standard_PCMLong))
+
+/* I2S Data Format */
+#define I2S_DataFormat_16b ((u16)0x0000)
+#define I2S_DataFormat_16bextended ((u16)0x0001)
+#define I2S_DataFormat_24b ((u16)0x0003)
+#define I2S_DataFormat_32b ((u16)0x0005)
+
+#define IS_I2S_DATA_FORMAT(FORMAT) (((FORMAT) == I2S_DataFormat_16b) || \
+ ((FORMAT) == I2S_DataFormat_16bextended) || \
+ ((FORMAT) == I2S_DataFormat_24b) || \
+ ((FORMAT) == I2S_DataFormat_32b))
+
+/* I2S MCLK Output */
+#define I2S_MCLKOutput_Enable ((u16)0x0200)
+#define I2S_MCLKOutput_Disable ((u16)0x0000)
+
+#define IS_I2S_MCLK_OUTPUT(OUTPUT) (((OUTPUT) == I2S_MCLKOutput_Enable) || \
+ ((OUTPUT) == I2S_MCLKOutput_Disable))
+
+/* I2S Audio Frequency */
+#define I2S_AudioFreq_48k ((u16)48000)
+#define I2S_AudioFreq_44k ((u16)44100)
+#define I2S_AudioFreq_22k ((u16)22050)
+#define I2S_AudioFreq_16k ((u16)16000)
+#define I2S_AudioFreq_8k ((u16)8000)
+#define I2S_AudioFreq_Default ((u16)2)
+
+#define IS_I2S_AUDIO_FREQ(FREQ) (((FREQ) == I2S_AudioFreq_48k) || \
+ ((FREQ) == I2S_AudioFreq_44k) || \
+ ((FREQ) == I2S_AudioFreq_22k) || \
+ ((FREQ) == I2S_AudioFreq_16k) || \
+ ((FREQ) == I2S_AudioFreq_8k) || \
+ ((FREQ) == I2S_AudioFreq_Default))
+
+/* I2S Clock Polarity */
+#define I2S_CPOL_Low ((u16)0x0000)
+#define I2S_CPOL_High ((u16)0x0008)
+
+#define IS_I2S_CPOL(CPOL) (((CPOL) == I2S_CPOL_Low) || \
+ ((CPOL) == I2S_CPOL_High))
+
+/* SPI_I2S DMA transfer requests */
+#define SPI_I2S_DMAReq_Tx ((u16)0x0002)
+#define SPI_I2S_DMAReq_Rx ((u16)0x0001)
+
+#define IS_SPI_I2S_DMAREQ(DMAREQ) ((((DMAREQ) & (u16)0xFFFC) == 0x00) && ((DMAREQ) != 0x00))
+
+/* SPI NSS internal software mangement */
+#define SPI_NSSInternalSoft_Set ((u16)0x0100)
+#define SPI_NSSInternalSoft_Reset ((u16)0xFEFF)
+
+#define IS_SPI_NSS_INTERNAL(INTERNAL) (((INTERNAL) == SPI_NSSInternalSoft_Set) || \
+ ((INTERNAL) == SPI_NSSInternalSoft_Reset))
+
+/* SPI CRC Transmit/Receive */
+#define SPI_CRC_Tx ((u8)0x00)
+#define SPI_CRC_Rx ((u8)0x01)
+
+#define IS_SPI_CRC(CRC) (((CRC) == SPI_CRC_Tx) || ((CRC) == SPI_CRC_Rx))
+
+/* SPI direction transmit/receive */
+#define SPI_Direction_Rx ((u16)0xBFFF)
+#define SPI_Direction_Tx ((u16)0x4000)
+
+#define IS_SPI_DIRECTION(DIRECTION) (((DIRECTION) == SPI_Direction_Rx) || \
+ ((DIRECTION) == SPI_Direction_Tx))
+
+/* SPI_I2S interrupts definition */
+#define SPI_I2S_IT_TXE ((u8)0x71)
+#define SPI_I2S_IT_RXNE ((u8)0x60)
+#define SPI_I2S_IT_ERR ((u8)0x50)
+
+#define IS_SPI_I2S_CONFIG_IT(IT) (((IT) == SPI_I2S_IT_TXE) || \
+ ((IT) == SPI_I2S_IT_RXNE) || \
+ ((IT) == SPI_I2S_IT_ERR))
+
+#define SPI_I2S_IT_OVR ((u8)0x56)
+#define SPI_IT_MODF ((u8)0x55)
+#define SPI_IT_CRCERR ((u8)0x54)
+#define I2S_IT_UDR ((u8)0x53)
+
+#define IS_SPI_I2S_CLEAR_IT(IT) (((IT) == SPI_I2S_IT_OVR) || \
+ ((IT) == SPI_IT_MODF) || \
+ ((IT) == SPI_IT_CRCERR) || \
+ ((IT) == I2S_IT_UDR))
+
+#define IS_SPI_I2S_GET_IT(IT) (((IT) == SPI_I2S_IT_RXNE) || ((IT) == SPI_I2S_IT_TXE) || \
+ ((IT) == I2S_IT_UDR) || ((IT) == SPI_IT_CRCERR) || \
+ ((IT) == SPI_IT_MODF) || ((IT) == SPI_I2S_IT_OVR))
+
+/* SPI_I2S flags definition */
+#define SPI_I2S_FLAG_RXNE ((u16)0x0001)
+#define SPI_I2S_FLAG_TXE ((u16)0x0002)
+#define I2S_FLAG_CHSIDE ((u16)0x0004)
+#define I2S_FLAG_UDR ((u16)0x0008)
+#define SPI_FLAG_CRCERR ((u16)0x0010)
+#define SPI_FLAG_MODF ((u16)0x0020)
+#define SPI_I2S_FLAG_OVR ((u16)0x0040)
+#define SPI_I2S_FLAG_BSY ((u16)0x0080)
+
+#define IS_SPI_I2S_CLEAR_FLAG(FLAG) (((FLAG) == SPI_I2S_FLAG_OVR) || ((FLAG) == SPI_FLAG_MODF) || \
+ ((FLAG) == SPI_FLAG_CRCERR) || ((FLAG) == I2S_FLAG_UDR))
+#define IS_SPI_I2S_GET_FLAG(FLAG) (((FLAG) == SPI_I2S_FLAG_BSY) || ((FLAG) == SPI_I2S_FLAG_OVR) || \
+ ((FLAG) == SPI_FLAG_MODF) || ((FLAG) == SPI_FLAG_CRCERR) || \
+ ((FLAG) == I2S_FLAG_UDR) || ((FLAG) == I2S_FLAG_CHSIDE) || \
+ ((FLAG) == SPI_I2S_FLAG_TXE) || ((FLAG) == SPI_I2S_FLAG_RXNE))
+
+/* SPI CRC polynomial --------------------------------------------------------*/
+#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL) ((POLYNOMIAL) >= 0x1)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void SPI_I2S_DeInit(SPI_TypeDef* SPIx);
+void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct);
+void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct);
+void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct);
+void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct);
+void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState);
+void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState);
+void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, u8 SPI_I2S_IT, FunctionalState NewState);
+void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, u16 SPI_I2S_DMAReq, FunctionalState NewState);
+void SPI_I2S_SendData(SPI_TypeDef* SPIx, u16 Data);
+u16 SPI_I2S_ReceiveData(SPI_TypeDef* SPIx);
+void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, u16 SPI_NSSInternalSoft);
+void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState);
+void SPI_DataSizeConfig(SPI_TypeDef* SPIx, u16 SPI_DataSize);
+void SPI_TransmitCRC(SPI_TypeDef* SPIx);
+void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState);
+u16 SPI_GetCRC(SPI_TypeDef* SPIx, u8 SPI_CRC);
+u16 SPI_GetCRCPolynomial(SPI_TypeDef* SPIx);
+void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, u16 SPI_Direction);
+FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, u16 SPI_I2S_FLAG);
+void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, u16 SPI_I2S_FLAG);
+ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, u8 SPI_I2S_IT);
+void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, u8 SPI_I2S_IT);
+
+#endif /*__STM32F10x_SPI_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_systick.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_systick.h new file mode 100755 index 0000000..5a5300f --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_systick.h @@ -0,0 +1,64 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_systick.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* SysTick firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_SYSTICK_H
+#define __STM32F10x_SYSTICK_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* SysTick clock source */
+#define SysTick_CLKSource_HCLK_Div8 ((u32)0xFFFFFFFB)
+#define SysTick_CLKSource_HCLK ((u32)0x00000004)
+
+#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \
+ ((SOURCE) == SysTick_CLKSource_HCLK_Div8))
+
+/* SysTick counter state */
+#define SysTick_Counter_Disable ((u32)0xFFFFFFFE)
+#define SysTick_Counter_Enable ((u32)0x00000001)
+#define SysTick_Counter_Clear ((u32)0x00000000)
+
+#define IS_SYSTICK_COUNTER(COUNTER) (((COUNTER) == SysTick_Counter_Disable) || \
+ ((COUNTER) == SysTick_Counter_Enable) || \
+ ((COUNTER) == SysTick_Counter_Clear))
+
+/* SysTick Flag */
+#define SysTick_FLAG_COUNT ((u32)0x00000010)
+#define SysTick_FLAG_SKEW ((u32)0x0000001E)
+#define SysTick_FLAG_NOREF ((u32)0x0000001F)
+
+#define IS_SYSTICK_FLAG(FLAG) (((FLAG) == SysTick_FLAG_COUNT) || \
+ ((FLAG) == SysTick_FLAG_SKEW) || \
+ ((FLAG) == SysTick_FLAG_NOREF))
+
+#define IS_SYSTICK_RELOAD(RELOAD) (((RELOAD) > 0) && ((RELOAD) <= 0xFFFFFF))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void SysTick_CLKSourceConfig(u32 SysTick_CLKSource);
+void SysTick_SetReload(u32 Reload);
+void SysTick_CounterCmd(u32 SysTick_Counter);
+void SysTick_ITConfig(FunctionalState NewState);
+u32 SysTick_GetCounter(void);
+FlagStatus SysTick_GetFlagStatus(u8 SysTick_FLAG);
+
+#endif /* __STM32F10x_SYSTICK_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_tim.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_tim.h new file mode 100755 index 0000000..1d024b8 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_tim.h @@ -0,0 +1,778 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_tim.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* TIM firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_TIM_H
+#define __STM32F10x_TIM_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+
+/* TIM Time Base Init structure definition */
+typedef struct
+{
+ u16 TIM_Prescaler;
+ u16 TIM_CounterMode;
+ u16 TIM_Period;
+ u16 TIM_ClockDivision;
+ u8 TIM_RepetitionCounter;
+} TIM_TimeBaseInitTypeDef;
+
+/* TIM Output Compare Init structure definition */
+typedef struct
+{
+ u16 TIM_OCMode;
+ u16 TIM_OutputState;
+ u16 TIM_OutputNState;
+ u16 TIM_Pulse;
+ u16 TIM_OCPolarity;
+ u16 TIM_OCNPolarity;
+ u16 TIM_OCIdleState;
+ u16 TIM_OCNIdleState;
+} TIM_OCInitTypeDef;
+
+/* TIM Input Capture Init structure definition */
+typedef struct
+{
+ u16 TIM_Channel;
+ u16 TIM_ICPolarity;
+ u16 TIM_ICSelection;
+ u16 TIM_ICPrescaler;
+ u16 TIM_ICFilter;
+} TIM_ICInitTypeDef;
+
+/* BDTR structure definition */
+typedef struct
+{
+ u16 TIM_OSSRState;
+ u16 TIM_OSSIState;
+ u16 TIM_LOCKLevel;
+ u16 TIM_DeadTime;
+ u16 TIM_Break;
+ u16 TIM_BreakPolarity;
+ u16 TIM_AutomaticOutput;
+} TIM_BDTRInitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+#define IS_TIM_ALL_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == TIM1_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM2_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM3_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM4_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM5_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM6_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM7_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM8_BASE))
+
+#define IS_TIM_18_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == TIM1_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM8_BASE))
+
+#define IS_TIM_123458_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == TIM1_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM2_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM3_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM4_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM5_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM8_BASE))
+
+/* TIM Output Compare and PWM modes -----------------------------------------*/
+#define TIM_OCMode_Timing ((u16)0x0000)
+#define TIM_OCMode_Active ((u16)0x0010)
+#define TIM_OCMode_Inactive ((u16)0x0020)
+#define TIM_OCMode_Toggle ((u16)0x0030)
+#define TIM_OCMode_PWM1 ((u16)0x0060)
+#define TIM_OCMode_PWM2 ((u16)0x0070)
+
+#define IS_TIM_OC_MODE(MODE) (((MODE) == TIM_OCMode_Timing) || \
+ ((MODE) == TIM_OCMode_Active) || \
+ ((MODE) == TIM_OCMode_Inactive) || \
+ ((MODE) == TIM_OCMode_Toggle)|| \
+ ((MODE) == TIM_OCMode_PWM1) || \
+ ((MODE) == TIM_OCMode_PWM2))
+
+#define IS_TIM_OCM(MODE) (((MODE) == TIM_OCMode_Timing) || \
+ ((MODE) == TIM_OCMode_Active) || \
+ ((MODE) == TIM_OCMode_Inactive) || \
+ ((MODE) == TIM_OCMode_Toggle)|| \
+ ((MODE) == TIM_OCMode_PWM1) || \
+ ((MODE) == TIM_OCMode_PWM2) || \
+ ((MODE) == TIM_ForcedAction_Active) || \
+ ((MODE) == TIM_ForcedAction_InActive))
+/* TIM One Pulse Mode -------------------------------------------------------*/
+#define TIM_OPMode_Single ((u16)0x0008)
+#define TIM_OPMode_Repetitive ((u16)0x0000)
+
+#define IS_TIM_OPM_MODE(MODE) (((MODE) == TIM_OPMode_Single) || \
+ ((MODE) == TIM_OPMode_Repetitive))
+
+/* TIM Channel -------------------------------------------------------------*/
+#define TIM_Channel_1 ((u16)0x0000)
+#define TIM_Channel_2 ((u16)0x0004)
+#define TIM_Channel_3 ((u16)0x0008)
+#define TIM_Channel_4 ((u16)0x000C)
+
+#define IS_TIM_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
+ ((CHANNEL) == TIM_Channel_2) || \
+ ((CHANNEL) == TIM_Channel_3) || \
+ ((CHANNEL) == TIM_Channel_4))
+
+#define IS_TIM_PWMI_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
+ ((CHANNEL) == TIM_Channel_2))
+
+#define IS_TIM_COMPLEMENTARY_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
+ ((CHANNEL) == TIM_Channel_2) || \
+ ((CHANNEL) == TIM_Channel_3))
+/* TIM Clock Division CKD --------------------------------------------------*/
+#define TIM_CKD_DIV1 ((u16)0x0000)
+#define TIM_CKD_DIV2 ((u16)0x0100)
+#define TIM_CKD_DIV4 ((u16)0x0200)
+
+#define IS_TIM_CKD_DIV(DIV) (((DIV) == TIM_CKD_DIV1) || \
+ ((DIV) == TIM_CKD_DIV2) || \
+ ((DIV) == TIM_CKD_DIV4))
+
+/* TIM Counter Mode --------------------------------------------------------*/
+#define TIM_CounterMode_Up ((u16)0x0000)
+#define TIM_CounterMode_Down ((u16)0x0010)
+#define TIM_CounterMode_CenterAligned1 ((u16)0x0020)
+#define TIM_CounterMode_CenterAligned2 ((u16)0x0040)
+#define TIM_CounterMode_CenterAligned3 ((u16)0x0060)
+
+#define IS_TIM_COUNTER_MODE(MODE) (((MODE) == TIM_CounterMode_Up) || \
+ ((MODE) == TIM_CounterMode_Down) || \
+ ((MODE) == TIM_CounterMode_CenterAligned1) || \
+ ((MODE) == TIM_CounterMode_CenterAligned2) || \
+ ((MODE) == TIM_CounterMode_CenterAligned3))
+
+/* TIM Output Compare Polarity ---------------------------------------------*/
+#define TIM_OCPolarity_High ((u16)0x0000)
+#define TIM_OCPolarity_Low ((u16)0x0002)
+
+#define IS_TIM_OC_POLARITY(POLARITY) (((POLARITY) == TIM_OCPolarity_High) || \
+ ((POLARITY) == TIM_OCPolarity_Low))
+
+/* TIM Output Compare N Polarity -------------------------------------------*/
+#define TIM_OCNPolarity_High ((u16)0x0000)
+#define TIM_OCNPolarity_Low ((u16)0x0008)
+
+#define IS_TIM_OCN_POLARITY(POLARITY) (((POLARITY) == TIM_OCNPolarity_High) || \
+ ((POLARITY) == TIM_OCNPolarity_Low))
+
+/* TIM Output Compare states -----------------------------------------------*/
+#define TIM_OutputState_Disable ((u16)0x0000)
+#define TIM_OutputState_Enable ((u16)0x0001)
+
+#define IS_TIM_OUTPUT_STATE(STATE) (((STATE) == TIM_OutputState_Disable) || \
+ ((STATE) == TIM_OutputState_Enable))
+
+/* TIM Output Compare N States ---------------------------------------------*/
+#define TIM_OutputNState_Disable ((u16)0x0000)
+#define TIM_OutputNState_Enable ((u16)0x0004)
+
+#define IS_TIM_OUTPUTN_STATE(STATE) (((STATE) == TIM_OutputNState_Disable) || \
+ ((STATE) == TIM_OutputNState_Enable))
+
+/* TIM Capture Compare States -----------------------------------------------*/
+#define TIM_CCx_Enable ((u16)0x0001)
+#define TIM_CCx_Disable ((u16)0x0000)
+
+#define IS_TIM_CCX(CCX) (((CCX) == TIM_CCx_Enable) || \
+ ((CCX) == TIM_CCx_Disable))
+
+/* TIM Capture Compare N States --------------------------------------------*/
+#define TIM_CCxN_Enable ((u16)0x0004)
+#define TIM_CCxN_Disable ((u16)0x0000)
+
+#define IS_TIM_CCXN(CCXN) (((CCXN) == TIM_CCxN_Enable) || \
+ ((CCXN) == TIM_CCxN_Disable))
+
+/* Break Input enable/disable -----------------------------------------------*/
+#define TIM_Break_Enable ((u16)0x1000)
+#define TIM_Break_Disable ((u16)0x0000)
+
+#define IS_TIM_BREAK_STATE(STATE) (((STATE) == TIM_Break_Enable) || \
+ ((STATE) == TIM_Break_Disable))
+
+/* Break Polarity -----------------------------------------------------------*/
+#define TIM_BreakPolarity_Low ((u16)0x0000)
+#define TIM_BreakPolarity_High ((u16)0x2000)
+
+#define IS_TIM_BREAK_POLARITY(POLARITY) (((POLARITY) == TIM_BreakPolarity_Low) || \
+ ((POLARITY) == TIM_BreakPolarity_High))
+
+/* TIM AOE Bit Set/Reset ---------------------------------------------------*/
+#define TIM_AutomaticOutput_Enable ((u16)0x4000)
+#define TIM_AutomaticOutput_Disable ((u16)0x0000)
+
+#define IS_TIM_AUTOMATIC_OUTPUT_STATE(STATE) (((STATE) == TIM_AutomaticOutput_Enable) || \
+ ((STATE) == TIM_AutomaticOutput_Disable))
+/* Lock levels --------------------------------------------------------------*/
+#define TIM_LOCKLevel_OFF ((u16)0x0000)
+#define TIM_LOCKLevel_1 ((u16)0x0100)
+#define TIM_LOCKLevel_2 ((u16)0x0200)
+#define TIM_LOCKLevel_3 ((u16)0x0300)
+
+#define IS_TIM_LOCK_LEVEL(LEVEL) (((LEVEL) == TIM_LOCKLevel_OFF) || \
+ ((LEVEL) == TIM_LOCKLevel_1) || \
+ ((LEVEL) == TIM_LOCKLevel_2) || \
+ ((LEVEL) == TIM_LOCKLevel_3))
+
+/* OSSI: Off-State Selection for Idle mode states ---------------------------*/
+#define TIM_OSSIState_Enable ((u16)0x0400)
+#define TIM_OSSIState_Disable ((u16)0x0000)
+
+#define IS_TIM_OSSI_STATE(STATE) (((STATE) == TIM_OSSIState_Enable) || \
+ ((STATE) == TIM_OSSIState_Disable))
+
+/* OSSR: Off-State Selection for Run mode states ----------------------------*/
+#define TIM_OSSRState_Enable ((u16)0x0800)
+#define TIM_OSSRState_Disable ((u16)0x0000)
+
+#define IS_TIM_OSSR_STATE(STATE) (((STATE) == TIM_OSSRState_Enable) || \
+ ((STATE) == TIM_OSSRState_Disable))
+
+/* TIM Output Compare Idle State -------------------------------------------*/
+#define TIM_OCIdleState_Set ((u16)0x0100)
+#define TIM_OCIdleState_Reset ((u16)0x0000)
+
+#define IS_TIM_OCIDLE_STATE(STATE) (((STATE) == TIM_OCIdleState_Set) || \
+ ((STATE) == TIM_OCIdleState_Reset))
+
+/* TIM Output Compare N Idle State -----------------------------------------*/
+#define TIM_OCNIdleState_Set ((u16)0x0200)
+#define TIM_OCNIdleState_Reset ((u16)0x0000)
+
+#define IS_TIM_OCNIDLE_STATE(STATE) (((STATE) == TIM_OCNIdleState_Set) || \
+ ((STATE) == TIM_OCNIdleState_Reset))
+
+/* TIM Input Capture Polarity ----------------------------------------------*/
+#define TIM_ICPolarity_Rising ((u16)0x0000)
+#define TIM_ICPolarity_Falling ((u16)0x0002)
+
+#define IS_TIM_IC_POLARITY(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \
+ ((POLARITY) == TIM_ICPolarity_Falling))
+
+/* TIM Input Capture Selection ---------------------------------------------*/
+#define TIM_ICSelection_DirectTI ((u16)0x0001)
+#define TIM_ICSelection_IndirectTI ((u16)0x0002)
+#define TIM_ICSelection_TRC ((u16)0x0003)
+
+#define IS_TIM_IC_SELECTION(SELECTION) (((SELECTION) == TIM_ICSelection_DirectTI) || \
+ ((SELECTION) == TIM_ICSelection_IndirectTI) || \
+ ((SELECTION) == TIM_ICSelection_TRC))
+
+/* TIM Input Capture Prescaler ---------------------------------------------*/
+#define TIM_ICPSC_DIV1 ((u16)0x0000)
+#define TIM_ICPSC_DIV2 ((u16)0x0004)
+#define TIM_ICPSC_DIV4 ((u16)0x0008)
+#define TIM_ICPSC_DIV8 ((u16)0x000C)
+
+#define IS_TIM_IC_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ICPSC_DIV1) || \
+ ((PRESCALER) == TIM_ICPSC_DIV2) || \
+ ((PRESCALER) == TIM_ICPSC_DIV4) || \
+ ((PRESCALER) == TIM_ICPSC_DIV8))
+
+/* TIM interrupt sources ---------------------------------------------------*/
+#define TIM_IT_Update ((u16)0x0001)
+#define TIM_IT_CC1 ((u16)0x0002)
+#define TIM_IT_CC2 ((u16)0x0004)
+#define TIM_IT_CC3 ((u16)0x0008)
+#define TIM_IT_CC4 ((u16)0x0010)
+#define TIM_IT_COM ((u16)0x0020)
+#define TIM_IT_Trigger ((u16)0x0040)
+#define TIM_IT_Break ((u16)0x0080)
+
+#define IS_TIM_IT(IT) ((((IT) & (u16)0xFF00) == 0x0000) && ((IT) != 0x0000))
+
+#define IS_TIM_PERIPH_IT(PERIPH, TIM_IT) ((((((*(u32*)&(PERIPH)) == TIM2_BASE) || (((*(u32*)&(PERIPH)) == TIM3_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM4_BASE)) || (((*(u32*)&(PERIPH)) == TIM5_BASE))))&& \
+ (((TIM_IT) & (u16)0xFFA0) == 0x0000) && ((TIM_IT) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM1_BASE) || (((*(u32*)&(PERIPH)) == TIM8_BASE))))&& \
+ (((TIM_IT) & (u16)0xFF00) == 0x0000) && ((TIM_IT) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM6_BASE) || (((*(u32*)&(PERIPH)) == TIM7_BASE))))&& \
+ (((TIM_IT) & (u16)0xFFFE) == 0x0000) && ((TIM_IT) != 0x0000)))
+
+#define IS_TIM_GET_IT(IT) (((IT) == TIM_IT_Update) || \
+ ((IT) == TIM_IT_CC1) || \
+ ((IT) == TIM_IT_CC2) || \
+ ((IT) == TIM_IT_CC3) || \
+ ((IT) == TIM_IT_CC4) || \
+ ((IT) == TIM_IT_COM) || \
+ ((IT) == TIM_IT_Trigger) || \
+ ((IT) == TIM_IT_Break))
+
+/* TIM DMA Base address ----------------------------------------------------*/
+#define TIM_DMABase_CR1 ((u16)0x0000)
+#define TIM_DMABase_CR2 ((u16)0x0001)
+#define TIM_DMABase_SMCR ((u16)0x0002)
+#define TIM_DMABase_DIER ((u16)0x0003)
+#define TIM_DMABase_SR ((u16)0x0004)
+#define TIM_DMABase_EGR ((u16)0x0005)
+#define TIM_DMABase_CCMR1 ((u16)0x0006)
+#define TIM_DMABase_CCMR2 ((u16)0x0007)
+#define TIM_DMABase_CCER ((u16)0x0008)
+#define TIM_DMABase_CNT ((u16)0x0009)
+#define TIM_DMABase_PSC ((u16)0x000A)
+#define TIM_DMABase_ARR ((u16)0x000B)
+#define TIM_DMABase_RCR ((u16)0x000C)
+#define TIM_DMABase_CCR1 ((u16)0x000D)
+#define TIM_DMABase_CCR2 ((u16)0x000E)
+#define TIM_DMABase_CCR3 ((u16)0x000F)
+#define TIM_DMABase_CCR4 ((u16)0x0010)
+#define TIM_DMABase_BDTR ((u16)0x0011)
+#define TIM_DMABase_DCR ((u16)0x0012)
+
+#define IS_TIM_DMA_BASE(BASE) (((BASE) == TIM_DMABase_CR1) || \
+ ((BASE) == TIM_DMABase_CR2) || \
+ ((BASE) == TIM_DMABase_SMCR) || \
+ ((BASE) == TIM_DMABase_DIER) || \
+ ((BASE) == TIM_DMABase_SR) || \
+ ((BASE) == TIM_DMABase_EGR) || \
+ ((BASE) == TIM_DMABase_CCMR1) || \
+ ((BASE) == TIM_DMABase_CCMR2) || \
+ ((BASE) == TIM_DMABase_CCER) || \
+ ((BASE) == TIM_DMABase_CNT) || \
+ ((BASE) == TIM_DMABase_PSC) || \
+ ((BASE) == TIM_DMABase_ARR) || \
+ ((BASE) == TIM_DMABase_RCR) || \
+ ((BASE) == TIM_DMABase_CCR1) || \
+ ((BASE) == TIM_DMABase_CCR2) || \
+ ((BASE) == TIM_DMABase_CCR3) || \
+ ((BASE) == TIM_DMABase_CCR4) || \
+ ((BASE) == TIM_DMABase_BDTR) || \
+ ((BASE) == TIM_DMABase_DCR))
+
+/* TIM DMA Burst Length ----------------------------------------------------*/
+#define TIM_DMABurstLength_1Byte ((u16)0x0000)
+#define TIM_DMABurstLength_2Bytes ((u16)0x0100)
+#define TIM_DMABurstLength_3Bytes ((u16)0x0200)
+#define TIM_DMABurstLength_4Bytes ((u16)0x0300)
+#define TIM_DMABurstLength_5Bytes ((u16)0x0400)
+#define TIM_DMABurstLength_6Bytes ((u16)0x0500)
+#define TIM_DMABurstLength_7Bytes ((u16)0x0600)
+#define TIM_DMABurstLength_8Bytes ((u16)0x0700)
+#define TIM_DMABurstLength_9Bytes ((u16)0x0800)
+#define TIM_DMABurstLength_10Bytes ((u16)0x0900)
+#define TIM_DMABurstLength_11Bytes ((u16)0x0A00)
+#define TIM_DMABurstLength_12Bytes ((u16)0x0B00)
+#define TIM_DMABurstLength_13Bytes ((u16)0x0C00)
+#define TIM_DMABurstLength_14Bytes ((u16)0x0D00)
+#define TIM_DMABurstLength_15Bytes ((u16)0x0E00)
+#define TIM_DMABurstLength_16Bytes ((u16)0x0F00)
+#define TIM_DMABurstLength_17Bytes ((u16)0x1000)
+#define TIM_DMABurstLength_18Bytes ((u16)0x1100)
+
+#define IS_TIM_DMA_LENGTH(LENGTH) (((LENGTH) == TIM_DMABurstLength_1Byte) || \
+ ((LENGTH) == TIM_DMABurstLength_2Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_3Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_4Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_5Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_6Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_7Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_8Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_9Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_10Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_11Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_12Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_13Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_14Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_15Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_16Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_17Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_18Bytes))
+
+/* TIM DMA sources ---------------------------------------------------------*/
+#define TIM_DMA_Update ((u16)0x0100)
+#define TIM_DMA_CC1 ((u16)0x0200)
+#define TIM_DMA_CC2 ((u16)0x0400)
+#define TIM_DMA_CC3 ((u16)0x0800)
+#define TIM_DMA_CC4 ((u16)0x1000)
+#define TIM_DMA_COM ((u16)0x2000)
+#define TIM_DMA_Trigger ((u16)0x4000)
+
+#define IS_TIM_DMA_SOURCE(SOURCE) ((((SOURCE) & (u16)0x80FF) == 0x0000) && ((SOURCE) != 0x0000))
+
+#define IS_TIM_PERIPH_DMA(PERIPH, SOURCE) ((((((*(u32*)&(PERIPH)) == TIM2_BASE) || (((*(u32*)&(PERIPH)) == TIM3_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM4_BASE)) || (((*(u32*)&(PERIPH)) == TIM5_BASE))))&& \
+ (((SOURCE) & (u16)0xA0FF) == 0x0000) && ((SOURCE) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM1_BASE) || (((*(u32*)&(PERIPH)) == TIM8_BASE))))&& \
+ (((SOURCE) & (u16)0x80FF) == 0x0000) && ((SOURCE) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM6_BASE) || (((*(u32*)&(PERIPH)) == TIM7_BASE))))&& \
+ (((SOURCE) & (u16)0xFEFF) == 0x0000) && ((SOURCE) != 0x0000)))
+
+/* TIM External Trigger Prescaler ------------------------------------------*/
+#define TIM_ExtTRGPSC_OFF ((u16)0x0000)
+#define TIM_ExtTRGPSC_DIV2 ((u16)0x1000)
+#define TIM_ExtTRGPSC_DIV4 ((u16)0x2000)
+#define TIM_ExtTRGPSC_DIV8 ((u16)0x3000)
+
+#define IS_TIM_EXT_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ExtTRGPSC_OFF) || \
+ ((PRESCALER) == TIM_ExtTRGPSC_DIV2) || \
+ ((PRESCALER) == TIM_ExtTRGPSC_DIV4) || \
+ ((PRESCALER) == TIM_ExtTRGPSC_DIV8))
+
+/* TIM Internal Trigger Selection ------------------------------------------*/
+#define TIM_TS_ITR0 ((u16)0x0000)
+#define TIM_TS_ITR1 ((u16)0x0010)
+#define TIM_TS_ITR2 ((u16)0x0020)
+#define TIM_TS_ITR3 ((u16)0x0030)
+#define TIM_TS_TI1F_ED ((u16)0x0040)
+#define TIM_TS_TI1FP1 ((u16)0x0050)
+#define TIM_TS_TI2FP2 ((u16)0x0060)
+#define TIM_TS_ETRF ((u16)0x0070)
+
+#define IS_TIM_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \
+ ((SELECTION) == TIM_TS_ITR1) || \
+ ((SELECTION) == TIM_TS_ITR2) || \
+ ((SELECTION) == TIM_TS_ITR3) || \
+ ((SELECTION) == TIM_TS_TI1F_ED) || \
+ ((SELECTION) == TIM_TS_TI1FP1) || \
+ ((SELECTION) == TIM_TS_TI2FP2) || \
+ ((SELECTION) == TIM_TS_ETRF))
+
+#define IS_TIM_INTERNAL_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \
+ ((SELECTION) == TIM_TS_ITR1) || \
+ ((SELECTION) == TIM_TS_ITR2) || \
+ ((SELECTION) == TIM_TS_ITR3))
+
+/* TIM TIx External Clock Source -------------------------------------------*/
+#define TIM_TIxExternalCLK1Source_TI1 ((u16)0x0050)
+#define TIM_TIxExternalCLK1Source_TI2 ((u16)0x0060)
+#define TIM_TIxExternalCLK1Source_TI1ED ((u16)0x0040)
+
+#define IS_TIM_TIXCLK_SOURCE(SOURCE) (((SOURCE) == TIM_TIxExternalCLK1Source_TI1) || \
+ ((SOURCE) == TIM_TIxExternalCLK1Source_TI2) || \
+ ((SOURCE) == TIM_TIxExternalCLK1Source_TI1ED))
+
+/* TIM External Trigger Polarity -------------------------------------------*/
+#define TIM_ExtTRGPolarity_Inverted ((u16)0x8000)
+#define TIM_ExtTRGPolarity_NonInverted ((u16)0x0000)
+
+#define IS_TIM_EXT_POLARITY(POLARITY) (((POLARITY) == TIM_ExtTRGPolarity_Inverted) || \
+ ((POLARITY) == TIM_ExtTRGPolarity_NonInverted))
+
+/* TIM Prescaler Reload Mode -----------------------------------------------*/
+#define TIM_PSCReloadMode_Update ((u16)0x0000)
+#define TIM_PSCReloadMode_Immediate ((u16)0x0001)
+
+#define IS_TIM_PRESCALER_RELOAD(RELOAD) (((RELOAD) == TIM_PSCReloadMode_Update) || \
+ ((RELOAD) == TIM_PSCReloadMode_Immediate))
+
+/* TIM Forced Action -------------------------------------------------------*/
+#define TIM_ForcedAction_Active ((u16)0x0050)
+#define TIM_ForcedAction_InActive ((u16)0x0040)
+
+#define IS_TIM_FORCED_ACTION(ACTION) (((ACTION) == TIM_ForcedAction_Active) || \
+ ((ACTION) == TIM_ForcedAction_InActive))
+
+/* TIM Encoder Mode --------------------------------------------------------*/
+#define TIM_EncoderMode_TI1 ((u16)0x0001)
+#define TIM_EncoderMode_TI2 ((u16)0x0002)
+#define TIM_EncoderMode_TI12 ((u16)0x0003)
+
+#define IS_TIM_ENCODER_MODE(MODE) (((MODE) == TIM_EncoderMode_TI1) || \
+ ((MODE) == TIM_EncoderMode_TI2) || \
+ ((MODE) == TIM_EncoderMode_TI12))
+
+/* TIM Event Source --------------------------------------------------------*/
+#define TIM_EventSource_Update ((u16)0x0001)
+#define TIM_EventSource_CC1 ((u16)0x0002)
+#define TIM_EventSource_CC2 ((u16)0x0004)
+#define TIM_EventSource_CC3 ((u16)0x0008)
+#define TIM_EventSource_CC4 ((u16)0x0010)
+#define TIM_EventSource_COM ((u16)0x0020)
+#define TIM_EventSource_Trigger ((u16)0x0040)
+#define TIM_EventSource_Break ((u16)0x0080)
+
+#define IS_TIM_EVENT_SOURCE(SOURCE) ((((SOURCE) & (u16)0xFF00) == 0x0000) && ((SOURCE) != 0x0000))
+
+#define IS_TIM_PERIPH_EVENT(PERIPH, EVENT) ((((((*(u32*)&(PERIPH)) == TIM2_BASE) || (((*(u32*)&(PERIPH)) == TIM3_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM4_BASE)) || (((*(u32*)&(PERIPH)) == TIM5_BASE))))&& \
+ (((EVENT) & (u16)0xFFA0) == 0x0000) && ((EVENT) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM1_BASE) || (((*(u32*)&(PERIPH)) == TIM8_BASE))))&& \
+ (((EVENT) & (u16)0xFF00) == 0x0000) && ((EVENT) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM6_BASE) || (((*(u32*)&(PERIPH)) == TIM7_BASE))))&& \
+ (((EVENT) & (u16)0xFFFE) == 0x0000) && ((EVENT) != 0x0000)))
+
+/* TIM Update Source --------------------------------------------------------*/
+#define TIM_UpdateSource_Global ((u16)0x0000)
+#define TIM_UpdateSource_Regular ((u16)0x0001)
+
+#define IS_TIM_UPDATE_SOURCE(SOURCE) (((SOURCE) == TIM_UpdateSource_Global) || \
+ ((SOURCE) == TIM_UpdateSource_Regular))
+
+/* TIM Ouput Compare Preload State ------------------------------------------*/
+#define TIM_OCPreload_Enable ((u16)0x0008)
+#define TIM_OCPreload_Disable ((u16)0x0000)
+
+#define IS_TIM_OCPRELOAD_STATE(STATE) (((STATE) == TIM_OCPreload_Enable) || \
+ ((STATE) == TIM_OCPreload_Disable))
+
+/* TIM Ouput Compare Fast State ---------------------------------------------*/
+#define TIM_OCFast_Enable ((u16)0x0004)
+#define TIM_OCFast_Disable ((u16)0x0000)
+
+#define IS_TIM_OCFAST_STATE(STATE) (((STATE) == TIM_OCFast_Enable) || \
+ ((STATE) == TIM_OCFast_Disable))
+
+/* TIM Ouput Compare Clear State --------------------------------------------*/
+#define TIM_OCClear_Enable ((u16)0x0080)
+#define TIM_OCClear_Disable ((u16)0x0000)
+
+#define IS_TIM_OCCLEAR_STATE(STATE) (((STATE) == TIM_OCClear_Enable) || \
+ ((STATE) == TIM_OCClear_Disable))
+
+/* TIM Trigger Output Source ------------------------------------------------*/
+#define TIM_TRGOSource_Reset ((u16)0x0000)
+#define TIM_TRGOSource_Enable ((u16)0x0010)
+#define TIM_TRGOSource_Update ((u16)0x0020)
+#define TIM_TRGOSource_OC1 ((u16)0x0030)
+#define TIM_TRGOSource_OC1Ref ((u16)0x0040)
+#define TIM_TRGOSource_OC2Ref ((u16)0x0050)
+#define TIM_TRGOSource_OC3Ref ((u16)0x0060)
+#define TIM_TRGOSource_OC4Ref ((u16)0x0070)
+
+#define IS_TIM_TRGO_SOURCE(SOURCE) (((SOURCE) == TIM_TRGOSource_Reset) || \
+ ((SOURCE) == TIM_TRGOSource_Enable) || \
+ ((SOURCE) == TIM_TRGOSource_Update) || \
+ ((SOURCE) == TIM_TRGOSource_OC1) || \
+ ((SOURCE) == TIM_TRGOSource_OC1Ref) || \
+ ((SOURCE) == TIM_TRGOSource_OC2Ref) || \
+ ((SOURCE) == TIM_TRGOSource_OC3Ref) || \
+ ((SOURCE) == TIM_TRGOSource_OC4Ref))
+
+#define IS_TIM_PERIPH_TRGO(PERIPH, TRGO) (((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM6_BASE))||(((*(u32*)&(PERIPH)) == TIM7_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_Reset)) ||\
+ ((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM6_BASE))||(((*(u32*)&(PERIPH)) == TIM7_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_Enable)) ||\
+ ((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM6_BASE))||(((*(u32*)&(PERIPH)) == TIM7_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_Update)) ||\
+ ((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_OC1)) ||\
+ ((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_OC1Ref)) ||\
+ ((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_OC2Ref)) ||\
+ ((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_OC3Ref)) ||\
+ ((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_OC4Ref)))
+
+/* TIM Slave Mode ----------------------------------------------------------*/
+#define TIM_SlaveMode_Reset ((u16)0x0004)
+#define TIM_SlaveMode_Gated ((u16)0x0005)
+#define TIM_SlaveMode_Trigger ((u16)0x0006)
+#define TIM_SlaveMode_External1 ((u16)0x0007)
+
+#define IS_TIM_SLAVE_MODE(MODE) (((MODE) == TIM_SlaveMode_Reset) || \
+ ((MODE) == TIM_SlaveMode_Gated) || \
+ ((MODE) == TIM_SlaveMode_Trigger) || \
+ ((MODE) == TIM_SlaveMode_External1))
+
+/* TIM Master Slave Mode ---------------------------------------------------*/
+#define TIM_MasterSlaveMode_Enable ((u16)0x0080)
+#define TIM_MasterSlaveMode_Disable ((u16)0x0000)
+
+#define IS_TIM_MSM_STATE(STATE) (((STATE) == TIM_MasterSlaveMode_Enable) || \
+ ((STATE) == TIM_MasterSlaveMode_Disable))
+
+/* TIM Flags ---------------------------------------------------------------*/
+#define TIM_FLAG_Update ((u16)0x0001)
+#define TIM_FLAG_CC1 ((u16)0x0002)
+#define TIM_FLAG_CC2 ((u16)0x0004)
+#define TIM_FLAG_CC3 ((u16)0x0008)
+#define TIM_FLAG_CC4 ((u16)0x0010)
+#define TIM_FLAG_COM ((u16)0x0020)
+#define TIM_FLAG_Trigger ((u16)0x0040)
+#define TIM_FLAG_Break ((u16)0x0080)
+#define TIM_FLAG_CC1OF ((u16)0x0200)
+#define TIM_FLAG_CC2OF ((u16)0x0400)
+#define TIM_FLAG_CC3OF ((u16)0x0800)
+#define TIM_FLAG_CC4OF ((u16)0x1000)
+
+#define IS_TIM_GET_FLAG(FLAG) (((FLAG) == TIM_FLAG_Update) || \
+ ((FLAG) == TIM_FLAG_CC1) || \
+ ((FLAG) == TIM_FLAG_CC2) || \
+ ((FLAG) == TIM_FLAG_CC3) || \
+ ((FLAG) == TIM_FLAG_CC4) || \
+ ((FLAG) == TIM_FLAG_COM) || \
+ ((FLAG) == TIM_FLAG_Trigger) || \
+ ((FLAG) == TIM_FLAG_Break) || \
+ ((FLAG) == TIM_FLAG_CC1OF) || \
+ ((FLAG) == TIM_FLAG_CC2OF) || \
+ ((FLAG) == TIM_FLAG_CC3OF) || \
+ ((FLAG) == TIM_FLAG_CC4OF))
+
+#define IS_TIM_CLEAR_FLAG(PERIPH, TIM_FLAG) ((((((*(u32*)&(PERIPH)) == TIM2_BASE) || (((*(u32*)&(PERIPH)) == TIM3_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM4_BASE)) || (((*(u32*)&(PERIPH)) == TIM5_BASE))))&& \
+ (((TIM_FLAG) & (u16)0xE1A0) == 0x0000) && ((TIM_FLAG) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM1_BASE) || (((*(u32*)&(PERIPH)) == TIM8_BASE))))&& \
+ (((TIM_FLAG) & (u16)0xE100) == 0x0000) && ((TIM_FLAG) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM6_BASE) || (((*(u32*)&(PERIPH)) == TIM7_BASE))))&& \
+ (((TIM_FLAG) & (u16)0xFFFE) == 0x0000) && ((TIM_FLAG) != 0x0000)))
+
+#define IS_TIM_PERIPH_FLAG(PERIPH, TIM_FLAG) (((((*(u32*)&(PERIPH))==TIM2_BASE) || ((*(u32*)&(PERIPH)) == TIM3_BASE) ||\
+ ((*(u32*)&(PERIPH)) == TIM4_BASE) || ((*(u32*)&(PERIPH))==TIM5_BASE) || \
+ ((*(u32*)&(PERIPH))==TIM1_BASE) || ((*(u32*)&(PERIPH))==TIM8_BASE)) &&\
+ (((TIM_FLAG) == TIM_FLAG_CC1) || ((TIM_FLAG) == TIM_FLAG_CC2) ||\
+ ((TIM_FLAG) == TIM_FLAG_CC3) || ((TIM_FLAG) == TIM_FLAG_CC4) || \
+ ((TIM_FLAG) == TIM_FLAG_Trigger))) ||\
+ ((((*(u32*)&(PERIPH))==TIM2_BASE) || ((*(u32*)&(PERIPH)) == TIM3_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM4_BASE) || ((*(u32*)&(PERIPH))==TIM5_BASE) ||\
+ ((*(u32*)&(PERIPH))==TIM1_BASE)|| ((*(u32*)&(PERIPH))==TIM8_BASE) || \
+ ((*(u32*)&(PERIPH))==TIM7_BASE) || ((*(u32*)&(PERIPH))==TIM6_BASE)) && \
+ (((TIM_FLAG) == TIM_FLAG_Update))) ||\
+ ((((*(u32*)&(PERIPH))==TIM1_BASE) || ((*(u32*)&(PERIPH)) == TIM8_BASE)) &&\
+ (((TIM_FLAG) == TIM_FLAG_COM) || ((TIM_FLAG) == TIM_FLAG_Break))) ||\
+ ((((*(u32*)&(PERIPH))==TIM2_BASE) || ((*(u32*)&(PERIPH)) == TIM3_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM4_BASE) || ((*(u32*)&(PERIPH))==TIM5_BASE) || \
+ ((*(u32*)&(PERIPH))==TIM1_BASE) || ((*(u32*)&(PERIPH))==TIM8_BASE)) &&\
+ (((TIM_FLAG) == TIM_FLAG_CC1OF) || ((TIM_FLAG) == TIM_FLAG_CC2OF) ||\
+ ((TIM_FLAG) == TIM_FLAG_CC3OF) || ((TIM_FLAG) == TIM_FLAG_CC4OF))))
+
+/* TIM Input Capture Filer Value ---------------------------------------------*/
+#define IS_TIM_IC_FILTER(ICFILTER) ((ICFILTER) <= 0xF)
+
+/* TIM External Trigger Filter -----------------------------------------------*/
+#define IS_TIM_EXT_FILTER(EXTFILTER) ((EXTFILTER) <= 0xF)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+
+void TIM_DeInit(TIM_TypeDef* TIMx);
+void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct);
+void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct);
+void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct);
+void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct);
+void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct);
+void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct);
+void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct);
+void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_ITConfig(TIM_TypeDef* TIMx, u16 TIM_IT, FunctionalState NewState);
+void TIM_GenerateEvent(TIM_TypeDef* TIMx, u16 TIM_EventSource);
+void TIM_DMAConfig(TIM_TypeDef* TIMx, u16 TIM_DMABase, u16 TIM_DMABurstLength);
+void TIM_DMACmd(TIM_TypeDef* TIMx, u16 TIM_DMASource, FunctionalState NewState);
+void TIM_InternalClockConfig(TIM_TypeDef* TIMx);
+void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, u16 TIM_InputTriggerSource);
+void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, u16 TIM_TIxExternalCLKSource,
+ u16 TIM_ICPolarity, u16 ICFilter);
+void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, u16 TIM_ExtTRGPrescaler, u16 TIM_ExtTRGPolarity,
+ u16 ExtTRGFilter);
+void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, u16 TIM_ExtTRGPrescaler,
+ u16 TIM_ExtTRGPolarity, u16 ExtTRGFilter);
+void TIM_ETRConfig(TIM_TypeDef* TIMx, u16 TIM_ExtTRGPrescaler, u16 TIM_ExtTRGPolarity,
+ u16 ExtTRGFilter);
+void TIM_PrescalerConfig(TIM_TypeDef* TIMx, u16 Prescaler, u16 TIM_PSCReloadMode);
+void TIM_CounterModeConfig(TIM_TypeDef* TIMx, u16 TIM_CounterMode);
+void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, u16 TIM_InputTriggerSource);
+void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, u16 TIM_EncoderMode,
+ u16 TIM_IC1Polarity, u16 TIM_IC2Polarity);
+void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction);
+void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction);
+void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction);
+void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction);
+void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload);
+void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload);
+void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload);
+void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload);
+void TIM_OC1FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast);
+void TIM_OC2FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast);
+void TIM_OC3FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast);
+void TIM_OC4FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast);
+void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear);
+void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear);
+void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear);
+void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear);
+void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity);
+void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCNPolarity);
+void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity);
+void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCNPolarity);
+void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity);
+void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCNPolarity);
+void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity);
+void TIM_CCxCmd(TIM_TypeDef* TIMx, u16 TIM_Channel, u16 TIM_CCx);
+void TIM_CCxNCmd(TIM_TypeDef* TIMx, u16 TIM_Channel, u16 TIM_CCxN);
+void TIM_SelectOCxM(TIM_TypeDef* TIMx, u16 TIM_Channel, u16 TIM_OCMode);
+void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, u16 TIM_UpdateSource);
+void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, u16 TIM_OPMode);
+void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, u16 TIM_TRGOSource);
+void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, u16 TIM_SlaveMode);
+void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, u16 TIM_MasterSlaveMode);
+void TIM_SetCounter(TIM_TypeDef* TIMx, u16 Counter);
+void TIM_SetAutoreload(TIM_TypeDef* TIMx, u16 Autoreload);
+void TIM_SetCompare1(TIM_TypeDef* TIMx, u16 Compare1);
+void TIM_SetCompare2(TIM_TypeDef* TIMx, u16 Compare2);
+void TIM_SetCompare3(TIM_TypeDef* TIMx, u16 Compare3);
+void TIM_SetCompare4(TIM_TypeDef* TIMx, u16 Compare4);
+void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC);
+void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC);
+void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC);
+void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC);
+void TIM_SetClockDivision(TIM_TypeDef* TIMx, u16 TIM_CKD);
+u16 TIM_GetCapture1(TIM_TypeDef* TIMx);
+u16 TIM_GetCapture2(TIM_TypeDef* TIMx);
+u16 TIM_GetCapture3(TIM_TypeDef* TIMx);
+u16 TIM_GetCapture4(TIM_TypeDef* TIMx);
+u16 TIM_GetCounter(TIM_TypeDef* TIMx);
+u16 TIM_GetPrescaler(TIM_TypeDef* TIMx);
+FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, u16 TIM_FLAG);
+void TIM_ClearFlag(TIM_TypeDef* TIMx, u16 TIM_FLAG);
+ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, u16 TIM_IT);
+void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, u16 TIM_IT);
+
+#endif /*__STM32F10x_TIM_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
+
+
+
+
+
+
+
+
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_type.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_type.h new file mode 100755 index 0000000..f17d0c4 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_type.h @@ -0,0 +1,80 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_type.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the common data types used for the
+* STM32F10x firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_TYPE_H
+#define __STM32F10x_TYPE_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+typedef signed long s32;
+typedef signed short s16;
+typedef signed char s8;
+
+typedef signed long const sc32; /* Read Only */
+typedef signed short const sc16; /* Read Only */
+typedef signed char const sc8; /* Read Only */
+
+typedef volatile signed long vs32;
+typedef volatile signed short vs16;
+typedef volatile signed char vs8;
+
+typedef volatile signed long const vsc32; /* Read Only */
+typedef volatile signed short const vsc16; /* Read Only */
+typedef volatile signed char const vsc8; /* Read Only */
+
+typedef unsigned long u32;
+typedef unsigned short u16;
+typedef unsigned char u8;
+
+typedef unsigned long const uc32; /* Read Only */
+typedef unsigned short const uc16; /* Read Only */
+typedef unsigned char const uc8; /* Read Only */
+
+typedef volatile unsigned long vu32;
+typedef volatile unsigned short vu16;
+typedef volatile unsigned char vu8;
+
+typedef volatile unsigned long const vuc32; /* Read Only */
+typedef volatile unsigned short const vuc16; /* Read Only */
+typedef volatile unsigned char const vuc8; /* Read Only */
+
+typedef enum {FALSE = 0, TRUE = !FALSE} bool;
+
+typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus;
+
+typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
+#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE))
+
+typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrorStatus;
+
+#define U8_MAX ((u8)255)
+#define S8_MAX ((s8)127)
+#define S8_MIN ((s8)-128)
+#define U16_MAX ((u16)65535u)
+#define S16_MAX ((s16)32767)
+#define S16_MIN ((s16)-32768)
+#define U32_MAX ((u32)4294967295uL)
+#define S32_MAX ((s32)2147483647)
+#define S32_MIN ((s32)-2147483648)
+
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __STM32F10x_TYPE_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_usart.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_usart.h new file mode 100755 index 0000000..cebc552 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_usart.h @@ -0,0 +1,256 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_usart.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* USART firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_USART_H
+#define __STM32F10x_USART_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* USART Init Structure definition */
+typedef struct
+{
+ u32 USART_BaudRate;
+ u16 USART_WordLength;
+ u16 USART_StopBits;
+ u16 USART_Parity;
+ u16 USART_Mode;
+ u16 USART_HardwareFlowControl;
+} USART_InitTypeDef;
+
+/* USART Clock Init Structure definition */
+typedef struct
+{
+ u16 USART_Clock;
+ u16 USART_CPOL;
+ u16 USART_CPHA;
+ u16 USART_LastBit;
+} USART_ClockInitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+#define IS_USART_ALL_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == USART1_BASE) || \
+ ((*(u32*)&(PERIPH)) == USART2_BASE) || \
+ ((*(u32*)&(PERIPH)) == USART3_BASE) || \
+ ((*(u32*)&(PERIPH)) == UART4_BASE) || \
+ ((*(u32*)&(PERIPH)) == UART5_BASE))
+
+#define IS_USART_123_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == USART1_BASE) || \
+ ((*(u32*)&(PERIPH)) == USART2_BASE) || \
+ ((*(u32*)&(PERIPH)) == USART3_BASE))
+
+#define IS_USART_1234_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == USART1_BASE) || \
+ ((*(u32*)&(PERIPH)) == USART2_BASE) || \
+ ((*(u32*)&(PERIPH)) == USART3_BASE) || \
+ ((*(u32*)&(PERIPH)) == UART4_BASE))
+
+/* USART Word Length ---------------------------------------------------------*/
+#define USART_WordLength_8b ((u16)0x0000)
+#define USART_WordLength_9b ((u16)0x1000)
+
+#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WordLength_8b) || \
+ ((LENGTH) == USART_WordLength_9b))
+
+/* USART Stop Bits -----------------------------------------------------------*/
+#define USART_StopBits_1 ((u16)0x0000)
+#define USART_StopBits_0_5 ((u16)0x1000)
+#define USART_StopBits_2 ((u16)0x2000)
+#define USART_StopBits_1_5 ((u16)0x3000)
+
+#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_StopBits_1) || \
+ ((STOPBITS) == USART_StopBits_0_5) || \
+ ((STOPBITS) == USART_StopBits_2) || \
+ ((STOPBITS) == USART_StopBits_1_5))
+/* USART Parity --------------------------------------------------------------*/
+#define USART_Parity_No ((u16)0x0000)
+#define USART_Parity_Even ((u16)0x0400)
+#define USART_Parity_Odd ((u16)0x0600)
+
+#define IS_USART_PARITY(PARITY) (((PARITY) == USART_Parity_No) || \
+ ((PARITY) == USART_Parity_Even) || \
+ ((PARITY) == USART_Parity_Odd))
+
+/* USART Mode ----------------------------------------------------------------*/
+#define USART_Mode_Rx ((u16)0x0004)
+#define USART_Mode_Tx ((u16)0x0008)
+
+#define IS_USART_MODE(MODE) ((((MODE) & (u16)0xFFF3) == 0x00) && ((MODE) != (u16)0x00))
+
+/* USART Hardware Flow Control -----------------------------------------------*/
+#define USART_HardwareFlowControl_None ((u16)0x0000)
+#define USART_HardwareFlowControl_RTS ((u16)0x0100)
+#define USART_HardwareFlowControl_CTS ((u16)0x0200)
+#define USART_HardwareFlowControl_RTS_CTS ((u16)0x0300)
+
+#define IS_USART_HARDWARE_FLOW_CONTROL(CONTROL)\
+ (((CONTROL) == USART_HardwareFlowControl_None) || \
+ ((CONTROL) == USART_HardwareFlowControl_RTS) || \
+ ((CONTROL) == USART_HardwareFlowControl_CTS) || \
+ ((CONTROL) == USART_HardwareFlowControl_RTS_CTS))
+
+#define IS_USART_PERIPH_HFC(PERIPH, HFC) ((((*(u32*)&(PERIPH)) != UART4_BASE) && \
+ ((*(u32*)&(PERIPH)) != UART5_BASE)) \
+ || ((HFC) == USART_HardwareFlowControl_None))
+
+/* USART Clock ---------------------------------------------------------------*/
+#define USART_Clock_Disable ((u16)0x0000)
+#define USART_Clock_Enable ((u16)0x0800)
+
+#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_Clock_Disable) || \
+ ((CLOCK) == USART_Clock_Enable))
+
+/* USART Clock Polarity ------------------------------------------------------*/
+#define USART_CPOL_Low ((u16)0x0000)
+#define USART_CPOL_High ((u16)0x0400)
+
+#define IS_USART_CPOL(CPOL) (((CPOL) == USART_CPOL_Low) || ((CPOL) == USART_CPOL_High))
+
+/* USART Clock Phase ---------------------------------------------------------*/
+#define USART_CPHA_1Edge ((u16)0x0000)
+#define USART_CPHA_2Edge ((u16)0x0200)
+#define IS_USART_CPHA(CPHA) (((CPHA) == USART_CPHA_1Edge) || ((CPHA) == USART_CPHA_2Edge))
+
+/* USART Last Bit ------------------------------------------------------------*/
+#define USART_LastBit_Disable ((u16)0x0000)
+#define USART_LastBit_Enable ((u16)0x0100)
+
+#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LastBit_Disable) || \
+ ((LASTBIT) == USART_LastBit_Enable))
+
+/* USART Interrupt definition ------------------------------------------------*/
+#define USART_IT_PE ((u16)0x0028)
+#define USART_IT_TXE ((u16)0x0727)
+#define USART_IT_TC ((u16)0x0626)
+#define USART_IT_RXNE ((u16)0x0525)
+#define USART_IT_IDLE ((u16)0x0424)
+#define USART_IT_LBD ((u16)0x0846)
+#define USART_IT_CTS ((u16)0x096A)
+#define USART_IT_ERR ((u16)0x0060)
+#define USART_IT_ORE ((u16)0x0360)
+#define USART_IT_NE ((u16)0x0260)
+#define USART_IT_FE ((u16)0x0160)
+
+#define IS_USART_CONFIG_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \
+ ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
+ ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \
+ ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ERR))
+
+#define IS_USART_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \
+ ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
+ ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \
+ ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ORE) || \
+ ((IT) == USART_IT_NE) || ((IT) == USART_IT_FE))
+
+#define IS_USART_CLEAR_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TC) || \
+ ((IT) == USART_IT_RXNE) || ((IT) == USART_IT_IDLE) || \
+ ((IT) == USART_IT_LBD) || ((IT) == USART_IT_CTS) || \
+ ((IT) == USART_IT_ORE) || ((IT) == USART_IT_NE) || \
+ ((IT) == USART_IT_FE))
+
+#define IS_USART_PERIPH_IT(PERIPH, USART_IT) ((((*(u32*)&(PERIPH)) != UART4_BASE) && \
+ ((*(u32*)&(PERIPH)) != UART5_BASE)) \
+ || ((USART_IT) != USART_IT_CTS))
+
+/* USART DMA Requests --------------------------------------------------------*/
+#define USART_DMAReq_Tx ((u16)0x0080)
+#define USART_DMAReq_Rx ((u16)0x0040)
+
+#define IS_USART_DMAREQ(DMAREQ) ((((DMAREQ) & (u16)0xFF3F) == 0x00) && ((DMAREQ) != (u16)0x00))
+
+/* USART WakeUp methods ------------------------------------------------------*/
+#define USART_WakeUp_IdleLine ((u16)0x0000)
+#define USART_WakeUp_AddressMark ((u16)0x0800)
+
+#define IS_USART_WAKEUP(WAKEUP) (((WAKEUP) == USART_WakeUp_IdleLine) || \
+ ((WAKEUP) == USART_WakeUp_AddressMark))
+
+/* USART LIN Break Detection Length ------------------------------------------*/
+#define USART_LINBreakDetectLength_10b ((u16)0x0000)
+#define USART_LINBreakDetectLength_11b ((u16)0x0020)
+
+#define IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH) \
+ (((LENGTH) == USART_LINBreakDetectLength_10b) || \
+ ((LENGTH) == USART_LINBreakDetectLength_11b))
+
+/* USART IrDA Low Power ------------------------------------------------------*/
+#define USART_IrDAMode_LowPower ((u16)0x0004)
+#define USART_IrDAMode_Normal ((u16)0x0000)
+
+#define IS_USART_IRDA_MODE(MODE) (((MODE) == USART_IrDAMode_LowPower) || \
+ ((MODE) == USART_IrDAMode_Normal))
+
+/* USART Flags ---------------------------------------------------------------*/
+#define USART_FLAG_CTS ((u16)0x0200)
+#define USART_FLAG_LBD ((u16)0x0100)
+#define USART_FLAG_TXE ((u16)0x0080)
+#define USART_FLAG_TC ((u16)0x0040)
+#define USART_FLAG_RXNE ((u16)0x0020)
+#define USART_FLAG_IDLE ((u16)0x0010)
+#define USART_FLAG_ORE ((u16)0x0008)
+#define USART_FLAG_NE ((u16)0x0004)
+#define USART_FLAG_FE ((u16)0x0002)
+#define USART_FLAG_PE ((u16)0x0001)
+
+#define IS_USART_FLAG(FLAG) (((FLAG) == USART_FLAG_PE) || ((FLAG) == USART_FLAG_TXE) || \
+ ((FLAG) == USART_FLAG_TC) || ((FLAG) == USART_FLAG_RXNE) || \
+ ((FLAG) == USART_FLAG_IDLE) || ((FLAG) == USART_FLAG_LBD) || \
+ ((FLAG) == USART_FLAG_CTS) || ((FLAG) == USART_FLAG_ORE) || \
+ ((FLAG) == USART_FLAG_NE) || ((FLAG) == USART_FLAG_FE))
+
+#define IS_USART_CLEAR_FLAG(FLAG) ((((FLAG) & (u16)0xFC80) == 0x00) && ((FLAG) != (u16)0x00))
+
+#define IS_USART_PERIPH_FLAG(PERIPH, USART_FLAG) ((((*(u32*)&(PERIPH)) != UART4_BASE) &&\
+ ((*(u32*)&(PERIPH)) != UART5_BASE)) \
+ || ((USART_FLAG) != USART_FLAG_CTS))
+
+#define IS_USART_BAUDRATE(BAUDRATE) (((BAUDRATE) > 0) && ((BAUDRATE) < 0x0044AA21))
+#define IS_USART_ADDRESS(ADDRESS) ((ADDRESS) <= 0xF)
+#define IS_USART_DATA(DATA) ((DATA) <= 0x1FF)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void USART_DeInit(USART_TypeDef* USARTx);
+void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct);
+void USART_StructInit(USART_InitTypeDef* USART_InitStruct);
+void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct);
+void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct);
+void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_ITConfig(USART_TypeDef* USARTx, u16 USART_IT, FunctionalState NewState);
+void USART_DMACmd(USART_TypeDef* USARTx, u16 USART_DMAReq, FunctionalState NewState);
+void USART_SetAddress(USART_TypeDef* USARTx, u8 USART_Address);
+void USART_WakeUpConfig(USART_TypeDef* USARTx, u16 USART_WakeUp);
+void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, u16 USART_LINBreakDetectLength);
+void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_SendData(USART_TypeDef* USARTx, u16 Data);
+u16 USART_ReceiveData(USART_TypeDef* USARTx);
+void USART_SendBreak(USART_TypeDef* USARTx);
+void USART_SetGuardTime(USART_TypeDef* USARTx, u8 USART_GuardTime);
+void USART_SetPrescaler(USART_TypeDef* USARTx, u8 USART_Prescaler);
+void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_IrDAConfig(USART_TypeDef* USARTx, u16 USART_IrDAMode);
+void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState);
+FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, u16 USART_FLAG);
+void USART_ClearFlag(USART_TypeDef* USARTx, u16 USART_FLAG);
+ITStatus USART_GetITStatus(USART_TypeDef* USARTx, u16 USART_IT);
+void USART_ClearITPendingBit(USART_TypeDef* USARTx, u16 USART_IT);
+
+#endif /* __STM32F10x_USART_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_wwdg.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_wwdg.h new file mode 100755 index 0000000..3a80626 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/inc/stm32f10x_wwdg.h @@ -0,0 +1,54 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_wwdg.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* WWDG firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_WWDG_H
+#define __STM32F10x_WWDG_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* WWDG Prescaler */
+#define WWDG_Prescaler_1 ((u32)0x00000000)
+#define WWDG_Prescaler_2 ((u32)0x00000080)
+#define WWDG_Prescaler_4 ((u32)0x00000100)
+#define WWDG_Prescaler_8 ((u32)0x00000180)
+
+#define IS_WWDG_PRESCALER(PRESCALER) (((PRESCALER) == WWDG_Prescaler_1) || \
+ ((PRESCALER) == WWDG_Prescaler_2) || \
+ ((PRESCALER) == WWDG_Prescaler_4) || \
+ ((PRESCALER) == WWDG_Prescaler_8))
+
+#define IS_WWDG_WINDOW_VALUE(VALUE) ((VALUE) <= 0x7F)
+
+#define IS_WWDG_COUNTER(COUNTER) (((COUNTER) >= 0x40) && ((COUNTER) <= 0x7F))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void WWDG_DeInit(void);
+void WWDG_SetPrescaler(u32 WWDG_Prescaler);
+void WWDG_SetWindowValue(u8 WindowValue);
+void WWDG_EnableIT(void);
+void WWDG_SetCounter(u8 Counter);
+void WWDG_Enable(u8 Counter);
+FlagStatus WWDG_GetFlagStatus(void);
+void WWDG_ClearFlag(void);
+
+#endif /* __STM32F10x_WWDG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/cortexm3_macro.s b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/cortexm3_macro.s new file mode 100755 index 0000000..b67be2e --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/cortexm3_macro.s @@ -0,0 +1,297 @@ +/*;******************** (C) COPYRIGHT 2007 STMicroelectronics ******************
+;* File Name : cortexm3_macro.s
+;* Author : MCD Application Team
+;* Version : V1.0
+;* Date : 10/08/2007
+;* Description : Instruction wrappers for special Cortex-M3 instructions.
+;*******************************************************************************
+; THE PRESENT SOFTWARE 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 SOFTWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
+; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+;******************************************************************************/
+ .cpu cortex-m3
+.fpu softvfp
+.syntax unified
+.thumb
+.text
+
+ /*; Exported functions*/
+ .globl __WFI
+ .globl __WFE
+ .globl __SEV
+ .globl __ISB
+ .globl __DSB
+ .globl __DMB
+ .globl __SVC
+ .globl __MRS_CONTROL
+ .globl __MSR_CONTROL
+ .globl __MRS_PSP
+ .globl __MSR_PSP
+ .globl __MRS_MSP
+ .globl __MSR_MSP
+ .globl __SETPRIMASK
+ .globl __RESETPRIMASK
+ .globl __SETFAULTMASK
+ .globl __RESETFAULTMASK
+ .globl __BASEPRICONFIG
+ .globl __GetBASEPRI
+ .globl __REV_HalfWord
+ .globl __REV_Word
+
+/*;*****************************************************************************
+; Function Name : __WFI
+; Description : Assembler function for the WFI instruction.
+; Input : None
+; Return : None
+;******************************************************************************/
+.thumb_func
+__WFI:
+
+ WFI
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __WFE
+; Description : Assembler function for the WFE instruction.
+; Input : None
+; Return : None
+;******************************************************************************/
+.thumb_func
+__WFE:
+
+ WFE
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __SEV
+; Description : Assembler function for the SEV instruction.
+; Input : None
+; Return : None
+;******************************************************************************/
+.thumb_func
+__SEV:
+
+ SEV
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __ISB
+; Description : Assembler function for the ISB instruction.
+; Input : None
+; Return : None
+;******************************************************************************/
+.thumb_func
+__ISB:
+
+ ISB
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __DSB
+; Description : Assembler function for the DSB instruction.
+; Input : None
+; Return : None
+;******************************************************************************/
+.thumb_func
+__DSB:
+
+ DSB
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __DMB
+; Description : Assembler function for the DMB instruction.
+; Input : None
+; Return : None
+;******************************************************************************/
+.thumb_func
+__DMB:
+
+ DMB
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __SVC
+; Description : Assembler function for the SVC instruction.
+; Input : None
+; Return : None
+;******************************************************************************/
+.thumb_func
+__SVC:
+
+ SVC 0x01
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __MRS_CONTROL
+; Description : Assembler function for the MRS instruction.
+; Input : None
+; Return : - r4 : Cortex-M3 CONTROL register value.
+;******************************************************************************/
+.thumb_func
+__MRS_CONTROL:
+
+ MRS r0,control
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __MSR_CONTROL
+; Description : Assembler function for the MSR instruction.
+; Input : - R0 : Cortex-M3 CONTROL register new value.
+; Return : None
+;******************************************************************************/
+.thumb_func
+__MSR_CONTROL:
+
+ MSR control, r0
+ ISB
+ BX r14
+/*;*****************************************************************************
+; Function Name : __MRS_PSP
+; Description : Assembler function for the MRS instruction.
+; Input : None
+; Return : - r0 : Process Stack value.
+;******************************************************************************/
+.thumb_func
+__MRS_PSP:
+
+ MRS r0, psp
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __MSR_PSP
+; Description : Assembler function for the MSR instruction.
+; Input : - r0 : Process Stack new value.
+; Return : None
+;******************************************************************************/
+.thumb_func
+__MSR_PSP:
+
+ MSR psp, r0 /* set Process Stack value*/
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __MRS_MSP
+; Description : Assembler function for the MRS instruction.
+; Input : None
+; Return : - r0 : Main Stack value.
+;******************************************************************************/
+.thumb_func
+__MRS_MSP:
+
+ MRS r0, msp
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __MSR_MSP
+; Description : Assembler function for the MSR instruction.
+; Input : - r0 : Main Stack new value.
+; Return : None
+;******************************************************************************/
+.thumb_func
+__MSR_MSP:
+
+ MSR msp, r0 /*; set Main Stack value*/
+ BX r14
+/*;*****************************************************************************
+; Function Name : __SETPRIMASK
+; Description : Assembler function to set the PRIMASK.
+; Input : None
+; Return : None
+;******************************************************************************/
+.thumb_func
+__SETPRIMASK:
+
+ CPSID i
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __RESETPRIMASK
+; Description : Assembler function to reset the PRIMASK.
+; Input : None
+; Return : None
+;******************************************************************************/
+.thumb_func
+__RESETPRIMASK:
+
+ CPSIE i
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __SETFAULTMASK
+; Description : Assembler function to set the FAULTMASK.
+; Input : None
+; Return : None
+;******************************************************************************/
+.thumb_func
+__SETFAULTMASK:
+
+ CPSID f
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __RESETFAULTMASK
+; Description : Assembler function to reset the FAULTMASK.
+; Input : None
+; Return : None
+;******************************************************************************/
+.thumb_func
+__RESETFAULTMASK:
+
+ CPSIE f
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __BASEPRICONFIG
+; Description : Assembler function to set the Base Priority.
+; Input : - r0 : Base Priority new value
+; Return : None
+;******************************************************************************/
+.thumb_func
+__BASEPRICONFIG:
+
+ MSR basepri, r0
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __GetBASEPRI
+; Description : Assembler function to get the Base Priority value.
+; Input : None
+; Return : - r0 : Base Priority value
+;******************************************************************************/
+.thumb_func
+__GetBASEPRI:
+
+ MRS r0, basepri_max
+ BX r14
+/*;*****************************************************************************
+; Function Name : __REV_HalfWord
+; Description : Reverses the byte order in HalfWord(16-bit) input variable.
+; Input : - r0 : specifies the input variable
+; Return : - r0 : holds tve variable value after byte reversing.
+;******************************************************************************/
+.thumb_func
+__REV_HalfWord:
+
+ REV16 r0, r0
+ BX r14
+
+/*;*****************************************************************************
+; Function Name : __REV_Word
+; Description : Reverses the byte order in Word(32-bit) input variable.
+; Input : - r0 : specifies the input variable
+; Return : - r0 : holds tve variable value after byte reversing.
+;******************************************************************************/
+.thumb_func
+__REV_Word:
+
+ REV r0, r0
+ BX r14
+
+.end
+
+
+/*;*************** (C) COPYRIGHT 2007 STMicroelectronics *****END OF FILE******/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_adc.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_adc.c new file mode 100755 index 0000000..47be673 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_adc.c @@ -0,0 +1,1402 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_adc.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the ADC firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_adc.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ADC DISCNUM mask */
+#define CR1_DISCNUM_Reset ((u32)0xFFFF1FFF)
+
+/* ADC DISCEN mask */
+#define CR1_DISCEN_Set ((u32)0x00000800)
+#define CR1_DISCEN_Reset ((u32)0xFFFFF7FF)
+
+/* ADC JAUTO mask */
+#define CR1_JAUTO_Set ((u32)0x00000400)
+#define CR1_JAUTO_Reset ((u32)0xFFFFFBFF)
+
+/* ADC JDISCEN mask */
+#define CR1_JDISCEN_Set ((u32)0x00001000)
+#define CR1_JDISCEN_Reset ((u32)0xFFFFEFFF)
+
+/* ADC AWDCH mask */
+#define CR1_AWDCH_Reset ((u32)0xFFFFFFE0)
+
+/* ADC Analog watchdog enable mode mask */
+#define CR1_AWDMode_Reset ((u32)0xFF3FFDFF)
+
+/* CR1 register Mask */
+#define CR1_CLEAR_Mask ((u32)0xFFF0FEFF)
+
+/* ADC ADON mask */
+#define CR2_ADON_Set ((u32)0x00000001)
+#define CR2_ADON_Reset ((u32)0xFFFFFFFE)
+
+/* ADC DMA mask */
+#define CR2_DMA_Set ((u32)0x00000100)
+#define CR2_DMA_Reset ((u32)0xFFFFFEFF)
+
+/* ADC RSTCAL mask */
+#define CR2_RSTCAL_Set ((u32)0x00000008)
+
+/* ADC CAL mask */
+#define CR2_CAL_Set ((u32)0x00000004)
+
+/* ADC SWSTART mask */
+#define CR2_SWSTART_Set ((u32)0x00400000)
+
+/* ADC EXTTRIG mask */
+#define CR2_EXTTRIG_Set ((u32)0x00100000)
+#define CR2_EXTTRIG_Reset ((u32)0xFFEFFFFF)
+
+/* ADC Software start mask */
+#define CR2_EXTTRIG_SWSTART_Set ((u32)0x00500000)
+#define CR2_EXTTRIG_SWSTART_Reset ((u32)0xFFAFFFFF)
+
+/* ADC JEXTSEL mask */
+#define CR2_JEXTSEL_Reset ((u32)0xFFFF8FFF)
+
+/* ADC JEXTTRIG mask */
+#define CR2_JEXTTRIG_Set ((u32)0x00008000)
+#define CR2_JEXTTRIG_Reset ((u32)0xFFFF7FFF)
+
+/* ADC JSWSTART mask */
+#define CR2_JSWSTART_Set ((u32)0x00200000)
+
+/* ADC injected software start mask */
+#define CR2_JEXTTRIG_JSWSTART_Set ((u32)0x00208000)
+#define CR2_JEXTTRIG_JSWSTART_Reset ((u32)0xFFDF7FFF)
+
+/* ADC TSPD mask */
+#define CR2_TSVREFE_Set ((u32)0x00800000)
+#define CR2_TSVREFE_Reset ((u32)0xFF7FFFFF)
+
+/* CR2 register Mask */
+#define CR2_CLEAR_Mask ((u32)0xFFF1F7FD)
+
+/* ADC SQx mask */
+#define SQR3_SQ_Set ((u32)0x0000001F)
+#define SQR2_SQ_Set ((u32)0x0000001F)
+#define SQR1_SQ_Set ((u32)0x0000001F)
+
+/* SQR1 register Mask */
+#define SQR1_CLEAR_Mask ((u32)0xFF0FFFFF)
+
+/* ADC JSQx mask */
+#define JSQR_JSQ_Set ((u32)0x0000001F)
+
+/* ADC JL mask */
+#define JSQR_JL_Set ((u32)0x00300000)
+#define JSQR_JL_Reset ((u32)0xFFCFFFFF)
+
+/* ADC SMPx mask */
+#define SMPR1_SMP_Set ((u32)0x00000007)
+#define SMPR2_SMP_Set ((u32)0x00000007)
+
+/* ADC JDRx registers offset */
+#define JDR_Offset ((u8)0x28)
+
+/* ADC1 DR register base address */
+#define DR_ADDRESS ((u32)0x4001244C)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : ADC_DeInit
+* Description : Deinitializes the ADCx peripheral registers to their default
+* reset values.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_DeInit(ADC_TypeDef* ADCx)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ switch (*(u32*)&ADCx)
+ {
+ case ADC1_BASE:
+ /* Enable ADC1 reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, ENABLE);
+ /* Release ADC1 from reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, DISABLE);
+ break;
+
+ case ADC2_BASE:
+ /* Enable ADC2 reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, ENABLE);
+ /* Release ADC2 from reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, DISABLE);
+ break;
+
+ case ADC3_BASE:
+ /* Enable ADC3 reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, ENABLE);
+ /* Release ADC3 from reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, DISABLE);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_Init
+* Description : Initializes the ADCx peripheral according to the specified parameters
+* in the ADC_InitStruct.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_InitStruct: pointer to an ADC_InitTypeDef structure that
+* contains the configuration information for the specified
+* ADC peripheral.
+* Output : None
+* Return : None
+******************************************************************************/
+void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct)
+{
+ u32 tmpreg1 = 0;
+ u8 tmpreg2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_MODE(ADC_InitStruct->ADC_Mode));
+ assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ScanConvMode));
+ assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ContinuousConvMode));
+ assert_param(IS_ADC_EXT_TRIG(ADC_InitStruct->ADC_ExternalTrigConv));
+ assert_param(IS_ADC_DATA_ALIGN(ADC_InitStruct->ADC_DataAlign));
+ assert_param(IS_ADC_REGULAR_LENGTH(ADC_InitStruct->ADC_NbrOfChannel));
+
+ /*---------------------------- ADCx CR1 Configuration -----------------*/
+ /* Get the ADCx CR1 value */
+ tmpreg1 = ADCx->CR1;
+ /* Clear DUALMOD and SCAN bits */
+ tmpreg1 &= CR1_CLEAR_Mask;
+ /* Configure ADCx: Dual mode and scan conversion mode */
+ /* Set DUALMOD bits according to ADC_Mode value */
+ /* Set SCAN bit according to ADC_ScanConvMode value */
+ tmpreg1 |= (u32)(ADC_InitStruct->ADC_Mode | ((u32)ADC_InitStruct->ADC_ScanConvMode << 8));
+ /* Write to ADCx CR1 */
+ ADCx->CR1 = tmpreg1;
+
+ /*---------------------------- ADCx CR2 Configuration -----------------*/
+ /* Get the ADCx CR2 value */
+ tmpreg1 = ADCx->CR2;
+ /* Clear CONT, ALIGN and EXTSEL bits */
+ tmpreg1 &= CR2_CLEAR_Mask;
+ /* Configure ADCx: external trigger event and continuous conversion mode */
+ /* Set ALIGN bit according to ADC_DataAlign value */
+ /* Set EXTSEL bits according to ADC_ExternalTrigConv value */
+ /* Set CONT bit according to ADC_ContinuousConvMode value */
+ tmpreg1 |= (u32)(ADC_InitStruct->ADC_DataAlign | ADC_InitStruct->ADC_ExternalTrigConv |
+ ((u32)ADC_InitStruct->ADC_ContinuousConvMode << 1));
+ /* Write to ADCx CR2 */
+ ADCx->CR2 = tmpreg1;
+
+ /*---------------------------- ADCx SQR1 Configuration -----------------*/
+ /* Get the ADCx SQR1 value */
+ tmpreg1 = ADCx->SQR1;
+ /* Clear L bits */
+ tmpreg1 &= SQR1_CLEAR_Mask;
+ /* Configure ADCx: regular channel sequence length */
+ /* Set L bits according to ADC_NbrOfChannel value */
+ tmpreg2 |= (ADC_InitStruct->ADC_NbrOfChannel - 1);
+ tmpreg1 |= ((u32)tmpreg2 << 20);
+ /* Write to ADCx SQR1 */
+ ADCx->SQR1 = tmpreg1;
+}
+
+/*******************************************************************************
+* Function Name : ADC_StructInit
+* Description : Fills each ADC_InitStruct member with its default value.
+* Input : ADC_InitStruct : pointer to an ADC_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct)
+{
+ /* Reset ADC init structure parameters values */
+ /* Initialize the ADC_Mode member */
+ ADC_InitStruct->ADC_Mode = ADC_Mode_Independent;
+
+ /* initialize the ADC_ScanConvMode member */
+ ADC_InitStruct->ADC_ScanConvMode = DISABLE;
+
+ /* Initialize the ADC_ContinuousConvMode member */
+ ADC_InitStruct->ADC_ContinuousConvMode = DISABLE;
+
+ /* Initialize the ADC_ExternalTrigConv member */
+ ADC_InitStruct->ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1;
+
+ /* Initialize the ADC_DataAlign member */
+ ADC_InitStruct->ADC_DataAlign = ADC_DataAlign_Right;
+
+ /* Initialize the ADC_NbrOfChannel member */
+ ADC_InitStruct->ADC_NbrOfChannel = 1;
+}
+
+/*******************************************************************************
+* Function Name : ADC_Cmd
+* Description : Enables or disables the specified ADC peripheral.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the ADCx peripheral. This parameter
+* can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Set the ADON bit to wake up the ADC from power down mode */
+ ADCx->CR2 |= CR2_ADON_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC peripheral */
+ ADCx->CR2 &= CR2_ADON_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_DMACmd
+* Description : Enables or disables the specified ADC DMA request.
+* Input : - ADCx: where x can be 1 or 3 to select the ADC peripheral.
+* Note: ADC2 hasn't a DMA capability.
+* - NewState: new state of the selected ADC DMA transfer.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_DMA_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC DMA request */
+ ADCx->CR2 |= CR2_DMA_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC DMA request */
+ ADCx->CR2 &= CR2_DMA_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_ITConfig
+* Description : Enables or disables the specified ADC interrupts.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_IT: specifies the ADC interrupt sources to be enabled
+* or disabled.
+* This parameter can be any combination of the following values:
+* - ADC_IT_EOC: End of conversion interrupt mask
+* - ADC_IT_AWD: Analog watchdog interrupt mask
+* - ADC_IT_JEOC: End of injected conversion interrupt mask
+* - NewState: new state of the specified ADC interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_ITConfig(ADC_TypeDef* ADCx, u16 ADC_IT, FunctionalState NewState)
+{
+ u8 itmask = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+ assert_param(IS_ADC_IT(ADC_IT));
+
+ /* Get the ADC IT index */
+ itmask = (u8)ADC_IT;
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC interrupts */
+ ADCx->CR1 |= itmask;
+ }
+ else
+ {
+ /* Disable the selected ADC interrupts */
+ ADCx->CR1 &= (~(u32)itmask);
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_ResetCalibration
+* Description : Resets the selected ADC calibration registers.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_ResetCalibration(ADC_TypeDef* ADCx)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ /* Resets the selected ADC calibartion registers */
+ ADCx->CR2 |= CR2_RSTCAL_Set;
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetResetCalibrationStatus
+* Description : Gets the selected ADC reset calibration registers status.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : The new state of ADC reset calibration registers (SET or RESET).
+*******************************************************************************/
+FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ /* Check the status of RSTCAL bit */
+ if ((ADCx->CR2 & CR2_RSTCAL_Set) != (u32)RESET)
+ {
+ /* RSTCAL bit is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* RSTCAL bit is reset */
+ bitstatus = RESET;
+ }
+
+ /* Return the RSTCAL bit status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : ADC_StartCalibration
+* Description : Starts the selected ADC calibration process.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_StartCalibration(ADC_TypeDef* ADCx)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ /* Enable the selected ADC calibration process */
+ ADCx->CR2 |= CR2_CAL_Set;
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetCalibrationStatus
+* Description : Gets the selected ADC calibration status.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : The new state of ADC calibration (SET or RESET).
+*******************************************************************************/
+FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ /* Check the status of CAL bit */
+ if ((ADCx->CR2 & CR2_CAL_Set) != (u32)RESET)
+ {
+ /* CAL bit is set: calibration on going */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* CAL bit is reset: end of calibration */
+ bitstatus = RESET;
+ }
+
+ /* Return the CAL bit status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : ADC_SoftwareStartConvCmd
+* Description : Enables or disables the selected ADC software start conversion .
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the selected ADC software start conversion.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC conversion on external event and start the selected
+ ADC conversion */
+ ADCx->CR2 |= CR2_EXTTRIG_SWSTART_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC conversion on external event and stop the selected
+ ADC conversion */
+ ADCx->CR2 &= CR2_EXTTRIG_SWSTART_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetSoftwareStartConvStatus
+* Description : Gets the selected ADC Software start conversion Status.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : The new state of ADC software start conversion (SET or RESET).
+*******************************************************************************/
+FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ /* Check the status of SWSTART bit */
+ if ((ADCx->CR2 & CR2_SWSTART_Set) != (u32)RESET)
+ {
+ /* SWSTART bit is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* SWSTART bit is reset */
+ bitstatus = RESET;
+ }
+
+ /* Return the SWSTART bit status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : ADC_DiscModeChannelCountConfig
+* Description : Configures the discontinuous mode for the selected ADC regular
+* group channel.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - Number: specifies the discontinuous mode regular channel
+* count value. This number must be between 1 and 8.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, u8 Number)
+{
+ u32 tmpreg1 = 0;
+ u32 tmpreg2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_REGULAR_DISC_NUMBER(Number));
+
+ /* Get the old register value */
+ tmpreg1 = ADCx->CR1;
+ /* Clear the old discontinuous mode channel count */
+ tmpreg1 &= CR1_DISCNUM_Reset;
+ /* Set the discontinuous mode channel count */
+ tmpreg2 = Number - 1;
+ tmpreg1 |= tmpreg2 << 13;
+ /* Store the new register value */
+ ADCx->CR1 = tmpreg1;
+}
+
+/*******************************************************************************
+* Function Name : ADC_DiscModeCmd
+* Description : Enables or disables the discontinuous mode on regular group
+* channel for the specified ADC
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the selected ADC discontinuous mode
+* on regular group channel.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC regular discontinuous mode */
+ ADCx->CR1 |= CR1_DISCEN_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC regular discontinuous mode */
+ ADCx->CR1 &= CR1_DISCEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_RegularChannelConfig
+* Description : Configures for the selected ADC regular channel its corresponding
+* rank in the sequencer and its sample time.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_Channel: the ADC channel to configure.
+* This parameter can be one of the following values:
+* - ADC_Channel_0: ADC Channel0 selected
+* - ADC_Channel_1: ADC Channel1 selected
+* - ADC_Channel_2: ADC Channel2 selected
+* - ADC_Channel_3: ADC Channel3 selected
+* - ADC_Channel_4: ADC Channel4 selected
+* - ADC_Channel_5: ADC Channel5 selected
+* - ADC_Channel_6: ADC Channel6 selected
+* - ADC_Channel_7: ADC Channel7 selected
+* - ADC_Channel_8: ADC Channel8 selected
+* - ADC_Channel_9: ADC Channel9 selected
+* - ADC_Channel_10: ADC Channel10 selected
+* - ADC_Channel_11: ADC Channel11 selected
+* - ADC_Channel_12: ADC Channel12 selected
+* - ADC_Channel_13: ADC Channel13 selected
+* - ADC_Channel_14: ADC Channel14 selected
+* - ADC_Channel_15: ADC Channel15 selected
+* - ADC_Channel_16: ADC Channel16 selected
+* - ADC_Channel_17: ADC Channel17 selected
+* - Rank: The rank in the regular group sequencer. This parameter
+* must be between 1 to 16.
+* - ADC_SampleTime: The sample time value to be set for the
+* selected channel.
+* This parameter can be one of the following values:
+* - ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles
+* - ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles
+* - ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles
+* - ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles
+* - ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles
+* - ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles
+* - ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles
+* - ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel, u8 Rank, u8 ADC_SampleTime)
+{
+ u32 tmpreg1 = 0, tmpreg2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_CHANNEL(ADC_Channel));
+ assert_param(IS_ADC_REGULAR_RANK(Rank));
+ assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime));
+
+ /* if ADC_Channel_10 ... ADC_Channel_17 is selected */
+ if (ADC_Channel > ADC_Channel_9)
+ {
+ /* Get the old register value */
+ tmpreg1 = ADCx->SMPR1;
+ /* Calculate the mask to clear */
+ tmpreg2 = SMPR1_SMP_Set << (3 * (ADC_Channel - 10));
+ /* Clear the old discontinuous mode channel count */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set */
+ tmpreg2 = (u32)ADC_SampleTime << (3 * (ADC_Channel - 10));
+ /* Set the discontinuous mode channel count */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->SMPR1 = tmpreg1;
+ }
+ else /* ADC_Channel include in ADC_Channel_[0..9] */
+ {
+ /* Get the old register value */
+ tmpreg1 = ADCx->SMPR2;
+ /* Calculate the mask to clear */
+ tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel);
+ /* Clear the old discontinuous mode channel count */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set */
+ tmpreg2 = (u32)ADC_SampleTime << (3 * ADC_Channel);
+ /* Set the discontinuous mode channel count */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->SMPR2 = tmpreg1;
+ }
+ /* For Rank 1 to 6 */
+ if (Rank < 7)
+ {
+ /* Get the old register value */
+ tmpreg1 = ADCx->SQR3;
+ /* Calculate the mask to clear */
+ tmpreg2 = SQR3_SQ_Set << (5 * (Rank - 1));
+ /* Clear the old SQx bits for the selected rank */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set */
+ tmpreg2 = (u32)ADC_Channel << (5 * (Rank - 1));
+ /* Set the SQx bits for the selected rank */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->SQR3 = tmpreg1;
+ }
+ /* For Rank 7 to 12 */
+ else if (Rank < 13)
+ {
+ /* Get the old register value */
+ tmpreg1 = ADCx->SQR2;
+ /* Calculate the mask to clear */
+ tmpreg2 = SQR2_SQ_Set << (5 * (Rank - 7));
+ /* Clear the old SQx bits for the selected rank */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set */
+ tmpreg2 = (u32)ADC_Channel << (5 * (Rank - 7));
+ /* Set the SQx bits for the selected rank */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->SQR2 = tmpreg1;
+ }
+ /* For Rank 13 to 16 */
+ else
+ {
+ /* Get the old register value */
+ tmpreg1 = ADCx->SQR1;
+ /* Calculate the mask to clear */
+ tmpreg2 = SQR1_SQ_Set << (5 * (Rank - 13));
+ /* Clear the old SQx bits for the selected rank */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set */
+ tmpreg2 = (u32)ADC_Channel << (5 * (Rank - 13));
+ /* Set the SQx bits for the selected rank */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->SQR1 = tmpreg1;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_ExternalTrigConvCmd
+* Description : Enables or disables the ADCx conversion through external trigger.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the selected ADC external trigger
+* start of conversion.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC conversion on external event */
+ ADCx->CR2 |= CR2_EXTTRIG_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC conversion on external event */
+ ADCx->CR2 &= CR2_EXTTRIG_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetConversionValue
+* Description : Returns the last ADCx conversion result data for regular channel.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : The Data conversion value.
+*******************************************************************************/
+u16 ADC_GetConversionValue(ADC_TypeDef* ADCx)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ /* Return the selected ADC conversion value */
+ return (u16) ADCx->DR;
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetDualModeConversionValue
+* Description : Returns the last ADC1 and ADC2 conversion result data in dual mode.
+* Output : None
+* Return : The Data conversion value.
+*******************************************************************************/
+u32 ADC_GetDualModeConversionValue(void)
+{
+ /* Return the dual mode conversion value */
+ return (*(vu32 *) DR_ADDRESS);
+}
+
+/*******************************************************************************
+* Function Name : ADC_AutoInjectedConvCmd
+* Description : Enables or disables the selected ADC automatic injected group
+* conversion after regular one.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the selected ADC auto injected
+* conversion
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC automatic injected group conversion */
+ ADCx->CR1 |= CR1_JAUTO_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC automatic injected group conversion */
+ ADCx->CR1 &= CR1_JAUTO_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_InjectedDiscModeCmd
+* Description : Enables or disables the discontinuous mode for injected group
+* channel for the specified ADC
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the selected ADC discontinuous mode
+* on injected group channel.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC injected discontinuous mode */
+ ADCx->CR1 |= CR1_JDISCEN_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC injected discontinuous mode */
+ ADCx->CR1 &= CR1_JDISCEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_ExternalTrigInjectedConvConfig
+* Description : Configures the ADCx external trigger for injected channels conversion.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_ExternalTrigInjecConv: specifies the ADC trigger to
+* start injected conversion.
+* This parameter can be one of the following values:
+* - ADC_ExternalTrigInjecConv_T1_TRGO: Timer1 TRGO event
+* selected (for ADC1, ADC2 and ADC3)
+* - ADC_ExternalTrigInjecConv_T1_CC4: Timer1 capture
+* compare4 selected (for ADC1, ADC2 and ADC3)
+* - ADC_ExternalTrigInjecConv_T2_TRGO: Timer2 TRGO event
+* selected (for ADC1 and ADC2)
+* - ADC_External TrigInjecConv_T2_CC1: Timer2 capture
+* compare1 selected (for ADC1 and ADC2)
+* - ADC_ExternalTrigInjecConv_T3_CC4: Timer3 capture
+* compare4 selected (for ADC1 and ADC2)
+* - ADC_ExternalTrigInjecConv_T4_TRGO: Timer4 TRGO event
+* selected (for ADC1 and ADC2)
+* - ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4: External
+* interrupt line 15 or Timer8 capture compare4 event selected
+* (for ADC1 and ADC2)
+* - ADC_External TrigInjecConv_T4_CC3: Timer4 capture
+* compare3 selected (for ADC3 only)
+* - ADC_External TrigInjecConv_T8_CC2: Timer8 capture
+* compare2 selected (for ADC3 only)
+* - ADC_External TrigInjecConv_T8_CC4: Timer8 capture
+* compare4 selected (for ADC3 only)
+* - ADC_ExternalTrigInjecConv_T5_TRGO: Timer5 TRGO event
+* selected (for ADC3 only)
+* - ADC_External TrigInjecConv_T5_CC4: Timer5 capture
+* compare4 selected (for ADC3 only)
+* - ADC_ExternalTrigInjecConv_None: Injected conversion
+* started by software and not by external trigger (for
+* ADC1, ADC2 and ADC3)
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, u32 ADC_ExternalTrigInjecConv)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_EXT_INJEC_TRIG(ADC_ExternalTrigInjecConv));
+
+ /* Get the old register value */
+ tmpreg = ADCx->CR2;
+ /* Clear the old external event selection for injected group */
+ tmpreg &= CR2_JEXTSEL_Reset;
+ /* Set the external event selection for injected group */
+ tmpreg |= ADC_ExternalTrigInjecConv;
+ /* Store the new register value */
+ ADCx->CR2 = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : ADC_ExternalTrigInjectedConvCmd
+* Description : Enables or disables the ADCx injected channels conversion
+* through external trigger
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the selected ADC external trigger
+* start of injected conversion.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC external event selection for injected group */
+ ADCx->CR2 |= CR2_JEXTTRIG_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC external event selection for injected group */
+ ADCx->CR2 &= CR2_JEXTTRIG_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_SoftwareStartInjectedConvCmd
+* Description : Enables or disables the selected ADC start of the injected
+* channels conversion.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the selected ADC software start
+* injected conversion.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC conversion for injected group on external event and start the selected
+ ADC injected conversion */
+ ADCx->CR2 |= CR2_JEXTTRIG_JSWSTART_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC conversion on external event for injected group and stop the selected
+ ADC injected conversion */
+ ADCx->CR2 &= CR2_JEXTTRIG_JSWSTART_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetSoftwareStartInjectedConvCmdStatus
+* Description : Gets the selected ADC Software start injected conversion Status.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : The new state of ADC software start injected conversion (SET or RESET).
+*******************************************************************************/
+FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ /* Check the status of JSWSTART bit */
+ if ((ADCx->CR2 & CR2_JSWSTART_Set) != (u32)RESET)
+ {
+ /* JSWSTART bit is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* JSWSTART bit is reset */
+ bitstatus = RESET;
+ }
+
+ /* Return the JSWSTART bit status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : ADC_InjectedChannelConfig
+* Description : Configures for the selected ADC injected channel its corresponding
+* rank in the sequencer and its sample time.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_Channel: the ADC channel to configure.
+* This parameter can be one of the following values:
+* - ADC_Channel_0: ADC Channel0 selected
+* - ADC_Channel_1: ADC Channel1 selected
+* - ADC_Channel_2: ADC Channel2 selected
+* - ADC_Channel_3: ADC Channel3 selected
+* - ADC_Channel_4: ADC Channel4 selected
+* - ADC_Channel_5: ADC Channel5 selected
+* - ADC_Channel_6: ADC Channel6 selected
+* - ADC_Channel_7: ADC Channel7 selected
+* - ADC_Channel_8: ADC Channel8 selected
+* - ADC_Channel_9: ADC Channel9 selected
+* - ADC_Channel_10: ADC Channel10 selected
+* - ADC_Channel_11: ADC Channel11 selected
+* - ADC_Channel_12: ADC Channel12 selected
+* - ADC_Channel_13: ADC Channel13 selected
+* - ADC_Channel_14: ADC Channel14 selected
+* - ADC_Channel_15: ADC Channel15 selected
+* - ADC_Channel_16: ADC Channel16 selected
+* - ADC_Channel_17: ADC Channel17 selected
+* - Rank: The rank in the injected group sequencer. This parameter
+* must be between 1 to 4.
+* - ADC_SampleTime: The sample time value to be set for the
+* selected channel.
+* This parameter can be one of the following values:
+* - ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles
+* - ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles
+* - ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles
+* - ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles
+* - ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles
+* - ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles
+* - ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles
+* - ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel, u8 Rank, u8 ADC_SampleTime)
+{
+ u32 tmpreg1 = 0, tmpreg2 = 0, tmpreg3 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_CHANNEL(ADC_Channel));
+ assert_param(IS_ADC_INJECTED_RANK(Rank));
+ assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime));
+
+ /* if ADC_Channel_10 ... ADC_Channel_17 is selected */
+ if (ADC_Channel > ADC_Channel_9)
+ {
+ /* Get the old register value */
+ tmpreg1 = ADCx->SMPR1;
+ /* Calculate the mask to clear */
+ tmpreg2 = SMPR1_SMP_Set << (3*(ADC_Channel - 10));
+ /* Clear the old discontinuous mode channel count */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set */
+ tmpreg2 = (u32)ADC_SampleTime << (3*(ADC_Channel - 10));
+ /* Set the discontinuous mode channel count */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->SMPR1 = tmpreg1;
+ }
+ else /* ADC_Channel include in ADC_Channel_[0..9] */
+ {
+ /* Get the old register value */
+ tmpreg1 = ADCx->SMPR2;
+ /* Calculate the mask to clear */
+ tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel);
+ /* Clear the old discontinuous mode channel count */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set */
+ tmpreg2 = (u32)ADC_SampleTime << (3 * ADC_Channel);
+ /* Set the discontinuous mode channel count */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->SMPR2 = tmpreg1;
+ }
+
+ /* Rank configuration */
+ /* Get the old register value */
+ tmpreg1 = ADCx->JSQR;
+ /* Get JL value: Number = JL+1 */
+ tmpreg3 = (tmpreg1 & JSQR_JL_Set)>> 20;
+ /* Calculate the mask to clear: ((Rank-1)+(4-JL-1)) */
+ tmpreg2 = JSQR_JSQ_Set << (5 * (u8)((Rank + 3) - (tmpreg3 + 1)));
+ /* Clear the old JSQx bits for the selected rank */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set: ((Rank-1)+(4-JL-1)) */
+ tmpreg2 = (u32)ADC_Channel << (5 * (u8)((Rank + 3) - (tmpreg3 + 1)));
+ /* Set the JSQx bits for the selected rank */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->JSQR = tmpreg1;
+}
+
+/*******************************************************************************
+* Function Name : ADC_InjectedSequencerLengthConfig
+* Description : Configures the sequencer length for injected channels
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - Length: The sequencer length.
+* This parameter must be a number between 1 to 4.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, u8 Length)
+{
+ u32 tmpreg1 = 0;
+ u32 tmpreg2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_INJECTED_LENGTH(Length));
+
+ /* Get the old register value */
+ tmpreg1 = ADCx->JSQR;
+ /* Clear the old injected sequnence lenght JL bits */
+ tmpreg1 &= JSQR_JL_Reset;
+ /* Set the injected sequnence lenght JL bits */
+ tmpreg2 = Length - 1;
+ tmpreg1 |= tmpreg2 << 20;
+ /* Store the new register value */
+ ADCx->JSQR = tmpreg1;
+}
+
+/*******************************************************************************
+* Function Name : ADC_SetInjectedOffset
+* Description : Set the injected channels conversion value offset
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_InjectedChannel: the ADC injected channel to set its
+* offset.
+* This parameter can be one of the following values:
+* - ADC_InjectedChannel_1: Injected Channel1 selected
+* - ADC_InjectedChannel_2: Injected Channel2 selected
+* - ADC_InjectedChannel_3: Injected Channel3 selected
+* - ADC_InjectedChannel_4: Injected Channel4 selected
+* - Offset: the offset value for the selected ADC injected channel
+* This parameter must be a 12bit value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, u8 ADC_InjectedChannel, u16 Offset)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel));
+ assert_param(IS_ADC_OFFSET(Offset));
+
+ /* Set the selected injected channel data offset */
+ *((vu32 *)((*(u32*)&ADCx) + ADC_InjectedChannel)) = (u32)Offset;
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetInjectedConversionValue
+* Description : Returns the ADC injected channel conversion result
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_InjectedChannel: the converted ADC injected channel.
+* This parameter can be one of the following values:
+* - ADC_InjectedChannel_1: Injected Channel1 selected
+* - ADC_InjectedChannel_2: Injected Channel2 selected
+* - ADC_InjectedChannel_3: Injected Channel3 selected
+* - ADC_InjectedChannel_4: Injected Channel4 selected
+* Output : None
+* Return : The Data conversion value.
+*******************************************************************************/
+u16 ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, u8 ADC_InjectedChannel)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel));
+
+ /* Returns the selected injected channel conversion data value */
+ return (u16) (*(vu32*) (((*(u32*)&ADCx) + ADC_InjectedChannel + JDR_Offset)));
+}
+
+/*******************************************************************************
+* Function Name : ADC_AnalogWatchdogCmd
+* Description : Enables or disables the analog watchdog on single/all regular
+* or injected channels
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_AnalogWatchdog: the ADC analog watchdog configuration.
+* This parameter can be one of the following values:
+* - ADC_AnalogWatchdog_SingleRegEnable: Analog watchdog on
+* a single regular channel
+* - ADC_AnalogWatchdog_SingleInjecEnable: Analog watchdog on
+* a single injected channel
+* - ADC_AnalogWatchdog_SingleRegOrInjecEnable: Analog
+* watchdog on a single regular or injected channel
+* - ADC_AnalogWatchdog_AllRegEnable: Analog watchdog on
+* all regular channel
+* - ADC_AnalogWatchdog_AllInjecEnable: Analog watchdog on
+* all injected channel
+* - ADC_AnalogWatchdog_AllRegAllInjecEnable: Analog watchdog
+* on all regular and injected channels
+* - ADC_AnalogWatchdog_None: No channel guarded by the
+* analog watchdog
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, u32 ADC_AnalogWatchdog)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_ANALOG_WATCHDOG(ADC_AnalogWatchdog));
+
+ /* Get the old register value */
+ tmpreg = ADCx->CR1;
+ /* Clear AWDEN, AWDENJ and AWDSGL bits */
+ tmpreg &= CR1_AWDMode_Reset;
+ /* Set the analog watchdog enable mode */
+ tmpreg |= ADC_AnalogWatchdog;
+ /* Store the new register value */
+ ADCx->CR1 = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : ADC_AnalogWatchdogThresholdsConfig
+* Description : Configures the high and low thresholds of the analog watchdog.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - HighThreshold: the ADC analog watchdog High threshold value.
+* This parameter must be a 12bit value.
+* - LowThreshold: the ADC analog watchdog Low threshold value.
+* This parameter must be a 12bit value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, u16 HighThreshold,
+ u16 LowThreshold)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_THRESHOLD(HighThreshold));
+ assert_param(IS_ADC_THRESHOLD(LowThreshold));
+
+ /* Set the ADCx high threshold */
+ ADCx->HTR = HighThreshold;
+ /* Set the ADCx low threshold */
+ ADCx->LTR = LowThreshold;
+}
+
+/*******************************************************************************
+* Function Name : ADC_AnalogWatchdogSingleChannelConfig
+* Description : Configures the analog watchdog guarded single channel
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_Channel: the ADC channel to configure for the analog
+* watchdog.
+* This parameter can be one of the following values:
+* - ADC_Channel_0: ADC Channel0 selected
+* - ADC_Channel_1: ADC Channel1 selected
+* - ADC_Channel_2: ADC Channel2 selected
+* - ADC_Channel_3: ADC Channel3 selected
+* - ADC_Channel_4: ADC Channel4 selected
+* - ADC_Channel_5: ADC Channel5 selected
+* - ADC_Channel_6: ADC Channel6 selected
+* - ADC_Channel_7: ADC Channel7 selected
+* - ADC_Channel_8: ADC Channel8 selected
+* - ADC_Channel_9: ADC Channel9 selected
+* - ADC_Channel_10: ADC Channel10 selected
+* - ADC_Channel_11: ADC Channel11 selected
+* - ADC_Channel_12: ADC Channel12 selected
+* - ADC_Channel_13: ADC Channel13 selected
+* - ADC_Channel_14: ADC Channel14 selected
+* - ADC_Channel_15: ADC Channel15 selected
+* - ADC_Channel_16: ADC Channel16 selected
+* - ADC_Channel_17: ADC Channel17 selected
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_CHANNEL(ADC_Channel));
+
+ /* Get the old register value */
+ tmpreg = ADCx->CR1;
+ /* Clear the Analog watchdog channel select bits */
+ tmpreg &= CR1_AWDCH_Reset;
+ /* Set the Analog watchdog channel */
+ tmpreg |= ADC_Channel;
+ /* Store the new register value */
+ ADCx->CR1 = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : ADC_TempSensorVrefintCmd
+* Description : Enables or disables the temperature sensor and Vrefint channel.
+* Input : - NewState: new state of the temperature sensor.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_TempSensorVrefintCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the temperature sensor and Vrefint channel*/
+ ADC1->CR2 |= CR2_TSVREFE_Set;
+ }
+ else
+ {
+ /* Disable the temperature sensor and Vrefint channel*/
+ ADC1->CR2 &= CR2_TSVREFE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetFlagStatus
+* Description : Checks whether the specified ADC flag is set or not.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - ADC_FLAG_AWD: Analog watchdog flag
+* - ADC_FLAG_EOC: End of conversion flag
+* - ADC_FLAG_JEOC: End of injected group conversion flag
+* - ADC_FLAG_JSTRT: Start of injected group conversion flag
+* - ADC_FLAG_STRT: Start of regular group conversion flag
+* Output : None
+* Return : The new state of ADC_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, u8 ADC_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_GET_FLAG(ADC_FLAG));
+
+ /* Check the status of the specified ADC flag */
+ if ((ADCx->SR & ADC_FLAG) != (u8)RESET)
+ {
+ /* ADC_FLAG is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* ADC_FLAG is reset */
+ bitstatus = RESET;
+ }
+
+ /* Return the ADC_FLAG status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : ADC_ClearFlag
+* Description : Clears the ADCx's pending flags.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_FLAG: specifies the flag to clear.
+* This parameter can be any combination of the following values:
+* - ADC_FLAG_AWD: Analog watchdog flag
+* - ADC_FLAG_EOC: End of conversion flag
+* - ADC_FLAG_JEOC: End of injected group conversion flag
+* - ADC_FLAG_JSTRT: Start of injected group conversion flag
+* - ADC_FLAG_STRT: Start of regular group conversion flag
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_ClearFlag(ADC_TypeDef* ADCx, u8 ADC_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_CLEAR_FLAG(ADC_FLAG));
+
+ /* Clear the selected ADC flags */
+ ADCx->SR = ~(u32)ADC_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetITStatus
+* Description : Checks whether the specified ADC interrupt has occurred or not.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_IT: specifies the ADC interrupt source to check.
+* This parameter can be one of the following values:
+* - ADC_IT_EOC: End of conversion interrupt mask
+* - ADC_IT_AWD: Analog watchdog interrupt mask
+* - ADC_IT_JEOC: End of injected conversion interrupt mask
+* Output : None
+* Return : The new state of ADC_IT (SET or RESET).
+*******************************************************************************/
+ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, u16 ADC_IT)
+{
+ ITStatus bitstatus = RESET;
+ u32 itmask = 0, enablestatus = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_GET_IT(ADC_IT));
+
+ /* Get the ADC IT index */
+ itmask = ADC_IT >> 8;
+
+ /* Get the ADC_IT enable bit status */
+ enablestatus = (ADCx->CR1 & (u8)ADC_IT) ;
+
+ /* Check the status of the specified ADC interrupt */
+ if (((ADCx->SR & itmask) != (u32)RESET) && enablestatus)
+ {
+ /* ADC_IT is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* ADC_IT is reset */
+ bitstatus = RESET;
+ }
+
+ /* Return the ADC_IT status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : ADC_ClearITPendingBit
+* Description : Clears the ADCx’s interrupt pending bits.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_IT: specifies the ADC interrupt pending bit to clear.
+* This parameter can be any combination of the following values:
+* - ADC_IT_EOC: End of conversion interrupt mask
+* - ADC_IT_AWD: Analog watchdog interrupt mask
+* - ADC_IT_JEOC: End of injected conversion interrupt mask
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, u16 ADC_IT)
+{
+ u8 itmask = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_IT(ADC_IT));
+
+ /* Get the ADC IT index */
+ itmask = (u8)(ADC_IT >> 8);
+
+ /* Clear the selected ADC interrupt pending bits */
+ ADCx->SR = ~(u32)itmask;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_bkp.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_bkp.c new file mode 100755 index 0000000..bc8755b --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_bkp.c @@ -0,0 +1,272 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_bkp.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the BKP firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_bkp.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ------------ BKP registers bit address in the alias region ----------- */
+#define BKP_OFFSET (BKP_BASE - PERIPH_BASE)
+
+/* --- CR Register ---*/
+/* Alias word address of TPAL bit */
+#define CR_OFFSET (BKP_OFFSET + 0x30)
+#define TPAL_BitNumber 0x01
+#define CR_TPAL_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPAL_BitNumber * 4))
+
+/* Alias word address of TPE bit */
+#define TPE_BitNumber 0x00
+#define CR_TPE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPE_BitNumber * 4))
+
+/* --- CSR Register ---*/
+/* Alias word address of TPIE bit */
+#define CSR_OFFSET (BKP_OFFSET + 0x34)
+#define TPIE_BitNumber 0x02
+#define CSR_TPIE_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TPIE_BitNumber * 4))
+
+/* Alias word address of TIF bit */
+#define TIF_BitNumber 0x09
+#define CSR_TIF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TIF_BitNumber * 4))
+
+/* Alias word address of TEF bit */
+#define TEF_BitNumber 0x08
+#define CSR_TEF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TEF_BitNumber * 4))
+
+
+/* ---------------------- BKP registers bit mask ------------------------ */
+/* RTCCR register bit mask */
+#define RTCCR_CAL_Mask ((u16)0xFF80)
+#define RTCCR_Mask ((u16)0xFC7F)
+
+/* CSR register bit mask */
+#define CSR_CTE_Set ((u16)0x0001)
+#define CSR_CTI_Set ((u16)0x0002)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : BKP_DeInit
+* Description : Deinitializes the BKP peripheral registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_DeInit(void)
+{
+ RCC_BackupResetCmd(ENABLE);
+ RCC_BackupResetCmd(DISABLE);
+}
+
+/*******************************************************************************
+* Function Name : BKP_TamperPinLevelConfig
+* Description : Configures the Tamper Pin active level.
+* Input : - BKP_TamperPinLevel: specifies the Tamper Pin active level.
+* This parameter can be one of the following values:
+* - BKP_TamperPinLevel_High: Tamper pin active on high level
+* - BKP_TamperPinLevel_Low: Tamper pin active on low level
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_TamperPinLevelConfig(u16 BKP_TamperPinLevel)
+{
+ /* Check the parameters */
+ assert_param(IS_BKP_TAMPER_PIN_LEVEL(BKP_TamperPinLevel));
+
+ *(vu32 *) CR_TPAL_BB = BKP_TamperPinLevel;
+}
+
+/*******************************************************************************
+* Function Name : BKP_TamperPinCmd
+* Description : Enables or disables the Tamper Pin activation.
+* Input : - NewState: new state of the Tamper Pin activation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_TamperPinCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CR_TPE_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : BKP_ITConfig
+* Description : Enables or disables the Tamper Pin Interrupt.
+* Input : - NewState: new state of the Tamper Pin Interrupt.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_ITConfig(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CSR_TPIE_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : BKP_RTCOutputConfig
+* Description : Select the RTC output source to output on the Tamper pin.
+* Input : - BKP_RTCOutputSource: specifies the RTC output source.
+* This parameter can be one of the following values:
+* - BKP_RTCOutputSource_None: no RTC output on the Tamper pin.
+* - BKP_RTCOutputSource_CalibClock: output the RTC clock
+* with frequency divided by 64 on the Tamper pin.
+* - BKP_RTCOutputSource_Alarm: output the RTC Alarm pulse
+* signal on the Tamper pin.
+* - BKP_RTCOutputSource_Second: output the RTC Second pulse
+* signal on the Tamper pin.
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_RTCOutputConfig(u16 BKP_RTCOutputSource)
+{
+ u16 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_BKP_RTC_OUTPUT_SOURCE(BKP_RTCOutputSource));
+
+ tmpreg = BKP->RTCCR;
+
+ /* Clear CCO, ASOE and ASOS bits */
+ tmpreg &= RTCCR_Mask;
+
+ /* Set CCO, ASOE and ASOS bits according to BKP_RTCOutputSource value */
+ tmpreg |= BKP_RTCOutputSource;
+
+ /* Store the new value */
+ BKP->RTCCR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : BKP_SetRTCCalibrationValue
+* Description : Sets RTC Clock Calibration value.
+* Input : - CalibrationValue: specifies the RTC Clock Calibration value.
+* This parameter must be a number between 0 and 0x7F.
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_SetRTCCalibrationValue(u8 CalibrationValue)
+{
+ u16 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_BKP_CALIBRATION_VALUE(CalibrationValue));
+
+ tmpreg = BKP->RTCCR;
+
+ /* Clear CAL[6:0] bits */
+ tmpreg &= RTCCR_CAL_Mask;
+
+ /* Set CAL[6:0] bits according to CalibrationValue value */
+ tmpreg |= CalibrationValue;
+
+ /* Store the new value */
+ BKP->RTCCR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : BKP_WriteBackupRegister
+* Description : Writes user data to the specified Data Backup Register.
+* Input : - BKP_DR: specifies the Data Backup Register.
+* This parameter can be BKP_DRx where x:[1, 42]
+* - Data: data to write
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_WriteBackupRegister(u16 BKP_DR, u16 Data)
+{
+ /* Check the parameters */
+ assert_param(IS_BKP_DR(BKP_DR));
+
+ *(vu16 *) (BKP_BASE + BKP_DR) = Data;
+}
+
+/*******************************************************************************
+* Function Name : BKP_ReadBackupRegister
+* Description : Reads data from the specified Data Backup Register.
+* Input : - BKP_DR: specifies the Data Backup Register.
+* This parameter can be BKP_DRx where x:[1, 42]
+* Output : None
+* Return : The content of the specified Data Backup Register
+*******************************************************************************/
+u16 BKP_ReadBackupRegister(u16 BKP_DR)
+{
+ /* Check the parameters */
+ assert_param(IS_BKP_DR(BKP_DR));
+
+ return (*(vu16 *) (BKP_BASE + BKP_DR));
+}
+
+/*******************************************************************************
+* Function Name : BKP_GetFlagStatus
+* Description : Checks whether the Tamper Pin Event flag is set or not.
+* Input : None
+* Output : None
+* Return : The new state of the Tamper Pin Event flag (SET or RESET).
+*******************************************************************************/
+FlagStatus BKP_GetFlagStatus(void)
+{
+ return (FlagStatus)(*(vu32 *) CSR_TEF_BB);
+}
+
+/*******************************************************************************
+* Function Name : BKP_ClearFlag
+* Description : Clears Tamper Pin Event pending flag.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_ClearFlag(void)
+{
+ /* Set CTE bit to clear Tamper Pin Event flag */
+ BKP->CSR |= CSR_CTE_Set;
+}
+
+/*******************************************************************************
+* Function Name : BKP_GetITStatus
+* Description : Checks whether the Tamper Pin Interrupt has occurred or not.
+* Input : None
+* Output : None
+* Return : The new state of the Tamper Pin Interrupt (SET or RESET).
+*******************************************************************************/
+ITStatus BKP_GetITStatus(void)
+{
+ return (ITStatus)(*(vu32 *) CSR_TIF_BB);
+}
+
+/*******************************************************************************
+* Function Name : BKP_ClearITPendingBit
+* Description : Clears Tamper Pin Interrupt pending bit.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_ClearITPendingBit(void)
+{
+ /* Set CTI bit to clear Tamper Pin Interrupt pending bit */
+ BKP->CSR |= CSR_CTI_Set;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_can.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_can.c new file mode 100755 index 0000000..a510e8a --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_can.c @@ -0,0 +1,907 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_can.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the CAN firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_can.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+
+/* Private define ------------------------------------------------------------*/
+/* CAN Master Control Register bits */
+#define CAN_MCR_INRQ ((u32)0x00000001) /* Initialization request */
+#define CAN_MCR_SLEEP ((u32)0x00000002) /* Sleep mode request */
+#define CAN_MCR_TXFP ((u32)0x00000004) /* Transmit FIFO priority */
+#define CAN_MCR_RFLM ((u32)0x00000008) /* Receive FIFO locked mode */
+#define CAN_MCR_NART ((u32)0x00000010) /* No automatic retransmission */
+#define CAN_MCR_AWUM ((u32)0x00000020) /* Automatic wake up mode */
+#define CAN_MCR_ABOM ((u32)0x00000040) /* Automatic bus-off management */
+#define CAN_MCR_TTCM ((u32)0x00000080) /* time triggered communication */
+
+/* CAN Master Status Register bits */
+#define CAN_MSR_INAK ((u32)0x00000001) /* Initialization acknowledge */
+#define CAN_MSR_WKUI ((u32)0x00000008) /* Wake-up interrupt */
+#define CAN_MSR_SLAKI ((u32)0x00000010) /* Sleep acknowledge interrupt */
+
+/* CAN Transmit Status Register bits */
+#define CAN_TSR_RQCP0 ((u32)0x00000001) /* Request completed mailbox0 */
+#define CAN_TSR_TXOK0 ((u32)0x00000002) /* Transmission OK of mailbox0 */
+#define CAN_TSR_ABRQ0 ((u32)0x00000080) /* Abort request for mailbox0 */
+#define CAN_TSR_RQCP1 ((u32)0x00000100) /* Request completed mailbox1 */
+#define CAN_TSR_TXOK1 ((u32)0x00000200) /* Transmission OK of mailbox1 */
+#define CAN_TSR_ABRQ1 ((u32)0x00008000) /* Abort request for mailbox1 */
+#define CAN_TSR_RQCP2 ((u32)0x00010000) /* Request completed mailbox2 */
+#define CAN_TSR_TXOK2 ((u32)0x00020000) /* Transmission OK of mailbox2 */
+#define CAN_TSR_ABRQ2 ((u32)0x00800000) /* Abort request for mailbox2 */
+#define CAN_TSR_TME0 ((u32)0x04000000) /* Transmit mailbox 0 empty */
+#define CAN_TSR_TME1 ((u32)0x08000000) /* Transmit mailbox 1 empty */
+#define CAN_TSR_TME2 ((u32)0x10000000) /* Transmit mailbox 2 empty */
+
+/* CAN Receive FIFO 0 Register bits */
+#define CAN_RF0R_FULL0 ((u32)0x00000008) /* FIFO 0 full */
+#define CAN_RF0R_FOVR0 ((u32)0x00000010) /* FIFO 0 overrun */
+#define CAN_RF0R_RFOM0 ((u32)0x00000020) /* Release FIFO 0 output mailbox */
+
+/* CAN Receive FIFO 1 Register bits */
+#define CAN_RF1R_FULL1 ((u32)0x00000008) /* FIFO 1 full */
+#define CAN_RF1R_FOVR1 ((u32)0x00000010) /* FIFO 1 overrun */
+#define CAN_RF1R_RFOM1 ((u32)0x00000020) /* Release FIFO 1 output mailbox */
+
+/* CAN Error Status Register bits */
+#define CAN_ESR_EWGF ((u32)0x00000001) /* Error warning flag */
+#define CAN_ESR_EPVF ((u32)0x00000002) /* Error passive flag */
+#define CAN_ESR_BOFF ((u32)0x00000004) /* Bus-off flag */
+
+/* CAN Mailbox Transmit Request */
+#define CAN_TMIDxR_TXRQ ((u32)0x00000001) /* Transmit mailbox request */
+
+/* CAN Filter Master Register bits */
+#define CAN_FMR_FINIT ((u32)0x00000001) /* Filter init mode */
+
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+static ITStatus CheckITStatus(u32 CAN_Reg, u32 It_Bit);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : CAN_DeInit
+* Description : Deinitializes the CAN peripheral registers to their default
+* reset values.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_DeInit(void)
+{
+ /* Enable CAN reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN, ENABLE);
+ /* Release CAN from reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN, DISABLE);
+}
+
+/*******************************************************************************
+* Function Name : CAN_Init
+* Description : Initializes the CAN peripheral according to the specified
+* parameters in the CAN_InitStruct.
+* Input : CAN_InitStruct: pointer to a CAN_InitTypeDef structure that
+ contains the configuration information for the CAN peripheral.
+* Output : None.
+* Return : Constant indicates initialization succeed which will be
+* CANINITFAILED or CANINITOK.
+*******************************************************************************/
+u8 CAN_Init(CAN_InitTypeDef* CAN_InitStruct)
+{
+ u8 InitStatus = 0;
+ u16 WaitAck;
+
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TTCM));
+ assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_ABOM));
+ assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_AWUM));
+ assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_NART));
+ assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_RFLM));
+ assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TXFP));
+ assert_param(IS_CAN_MODE(CAN_InitStruct->CAN_Mode));
+ assert_param(IS_CAN_SJW(CAN_InitStruct->CAN_SJW));
+ assert_param(IS_CAN_BS1(CAN_InitStruct->CAN_BS1));
+ assert_param(IS_CAN_BS2(CAN_InitStruct->CAN_BS2));
+ assert_param(IS_CAN_PRESCALER(CAN_InitStruct->CAN_Prescaler));
+
+ /* Request initialisation */
+ CAN->MCR = CAN_MCR_INRQ;
+
+ /* ...and check acknowledged */
+ if ((CAN->MSR & CAN_MSR_INAK) == 0)
+ {
+ InitStatus = CANINITFAILED;
+ }
+ else
+ {
+ /* Set the time triggered communication mode */
+ if (CAN_InitStruct->CAN_TTCM == ENABLE)
+ {
+ CAN->MCR |= CAN_MCR_TTCM;
+ }
+ else
+ {
+ CAN->MCR &= ~CAN_MCR_TTCM;
+ }
+
+ /* Set the automatic bus-off management */
+ if (CAN_InitStruct->CAN_ABOM == ENABLE)
+ {
+ CAN->MCR |= CAN_MCR_ABOM;
+ }
+ else
+ {
+ CAN->MCR &= ~CAN_MCR_ABOM;
+ }
+
+ /* Set the automatic wake-up mode */
+ if (CAN_InitStruct->CAN_AWUM == ENABLE)
+ {
+ CAN->MCR |= CAN_MCR_AWUM;
+ }
+ else
+ {
+ CAN->MCR &= ~CAN_MCR_AWUM;
+ }
+
+ /* Set the no automatic retransmission */
+ if (CAN_InitStruct->CAN_NART == ENABLE)
+ {
+ CAN->MCR |= CAN_MCR_NART;
+ }
+ else
+ {
+ CAN->MCR &= ~CAN_MCR_NART;
+ }
+
+ /* Set the receive FIFO locked mode */
+ if (CAN_InitStruct->CAN_RFLM == ENABLE)
+ {
+ CAN->MCR |= CAN_MCR_RFLM;
+ }
+ else
+ {
+ CAN->MCR &= ~CAN_MCR_RFLM;
+ }
+
+ /* Set the transmit FIFO priority */
+ if (CAN_InitStruct->CAN_TXFP == ENABLE)
+ {
+ CAN->MCR |= CAN_MCR_TXFP;
+ }
+ else
+ {
+ CAN->MCR &= ~CAN_MCR_TXFP;
+ }
+
+ /* Set the bit timing register */
+ CAN->BTR = (u32)((u32)CAN_InitStruct->CAN_Mode << 30) | ((u32)CAN_InitStruct->CAN_SJW << 24) |
+ ((u32)CAN_InitStruct->CAN_BS1 << 16) | ((u32)CAN_InitStruct->CAN_BS2 << 20) |
+ ((u32)CAN_InitStruct->CAN_Prescaler - 1);
+
+ InitStatus = CANINITOK;
+
+ /* Request leave initialisation */
+ CAN->MCR &= ~CAN_MCR_INRQ;
+
+ /* Wait the acknowledge */
+ for(WaitAck = 0x400; WaitAck > 0x0; WaitAck--)
+ {
+ }
+
+ /* ...and check acknowledged */
+ if ((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK)
+ {
+ InitStatus = CANINITFAILED;
+ }
+ }
+
+ /* At this step, return the status of initialization */
+ return InitStatus;
+}
+
+/*******************************************************************************
+* Function Name : CAN_FilterInit
+* Description : Initializes the CAN peripheral according to the specified
+* parameters in the CAN_FilterInitStruct.
+* Input : CAN_FilterInitStruct: pointer to a CAN_FilterInitTypeDef
+* structure that contains the configuration information.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct)
+{
+ u16 FilterNumber_BitPos = 0;
+
+ /* Check the parameters */
+ assert_param(IS_CAN_FILTER_NUMBER(CAN_FilterInitStruct->CAN_FilterNumber));
+ assert_param(IS_CAN_FILTER_MODE(CAN_FilterInitStruct->CAN_FilterMode));
+ assert_param(IS_CAN_FILTER_SCALE(CAN_FilterInitStruct->CAN_FilterScale));
+ assert_param(IS_CAN_FILTER_FIFO(CAN_FilterInitStruct->CAN_FilterFIFOAssignment));
+ assert_param(IS_FUNCTIONAL_STATE(CAN_FilterInitStruct->CAN_FilterActivation));
+
+ FilterNumber_BitPos =
+ (u16)((u16)0x0001 << ((u16)CAN_FilterInitStruct->CAN_FilterNumber));
+
+ /* Initialisation mode for the filter */
+ CAN->FMR |= CAN_FMR_FINIT;
+
+ /* Filter Deactivation */
+ CAN->FA1R &= ~(u32)FilterNumber_BitPos;
+
+ /* Filter Scale */
+ if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_16bit)
+ {
+ /* 16-bit scale for the filter */
+ CAN->FS1R &= ~(u32)FilterNumber_BitPos;
+
+ /* First 16-bit identifier and First 16-bit mask */
+ /* Or First 16-bit identifier and Second 16-bit identifier */
+ CAN->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 =
+ ((u32)((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterMaskIdLow) << 16) |
+ ((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterIdLow);
+
+ /* Second 16-bit identifier and Second 16-bit mask */
+ /* Or Third 16-bit identifier and Fourth 16-bit identifier */
+ CAN->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 =
+ ((u32)((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) |
+ ((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterIdHigh);
+ }
+ if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_32bit)
+ {
+ /* 32-bit scale for the filter */
+ CAN->FS1R |= FilterNumber_BitPos;
+
+ /* 32-bit identifier or First 32-bit identifier */
+ CAN->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 =
+ ((u32)((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterIdHigh) << 16) |
+ ((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterIdLow);
+
+ /* 32-bit mask or Second 32-bit identifier */
+ CAN->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 =
+ ((u32)((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) |
+ ((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterMaskIdLow);
+
+ }
+
+ /* Filter Mode */
+ if (CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdMask)
+ {
+ /*Id/Mask mode for the filter*/
+ CAN->FM1R &= ~(u32)FilterNumber_BitPos;
+ }
+ else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */
+ {
+ /*Identifier list mode for the filter*/
+ CAN->FM1R |= (u32)FilterNumber_BitPos;
+ }
+
+ /* Filter FIFO assignment */
+ if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_FilterFIFO0)
+ {
+ /* FIFO 0 assignation for the filter */
+ CAN->FFA1R &= ~(u32)FilterNumber_BitPos;
+ }
+ if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_FilterFIFO1)
+ {
+ /* FIFO 1 assignation for the filter */
+ CAN->FFA1R |= (u32)FilterNumber_BitPos;
+ }
+
+ /* Filter activation */
+ if (CAN_FilterInitStruct->CAN_FilterActivation == ENABLE)
+ {
+ CAN->FA1R |= FilterNumber_BitPos;
+ }
+
+ /* Leave the initialisation mode for the filter */
+ CAN->FMR &= ~CAN_FMR_FINIT;
+}
+
+/*******************************************************************************
+* Function Name : CAN_StructInit
+* Description : Fills each CAN_InitStruct member with its default value.
+* Input : CAN_InitStruct: pointer to a CAN_InitTypeDef structure which
+* will be initialized.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct)
+{
+ /* Reset CAN init structure parameters values */
+
+ /* Initialize the time triggered communication mode */
+ CAN_InitStruct->CAN_TTCM = DISABLE;
+
+ /* Initialize the automatic bus-off management */
+ CAN_InitStruct->CAN_ABOM = DISABLE;
+
+ /* Initialize the automatic wake-up mode */
+ CAN_InitStruct->CAN_AWUM = DISABLE;
+
+ /* Initialize the no automatic retransmission */
+ CAN_InitStruct->CAN_NART = DISABLE;
+
+ /* Initialize the receive FIFO locked mode */
+ CAN_InitStruct->CAN_RFLM = DISABLE;
+
+ /* Initialize the transmit FIFO priority */
+ CAN_InitStruct->CAN_TXFP = DISABLE;
+
+ /* Initialize the CAN_Mode member */
+ CAN_InitStruct->CAN_Mode = CAN_Mode_Normal;
+
+ /* Initialize the CAN_SJW member */
+ CAN_InitStruct->CAN_SJW = CAN_SJW_1tq;
+
+ /* Initialize the CAN_BS1 member */
+ CAN_InitStruct->CAN_BS1 = CAN_BS1_4tq;
+
+ /* Initialize the CAN_BS2 member */
+ CAN_InitStruct->CAN_BS2 = CAN_BS2_3tq;
+
+ /* Initialize the CAN_Prescaler member */
+ CAN_InitStruct->CAN_Prescaler = 1;
+}
+
+/*******************************************************************************
+* Function Name : CAN_ITConfig
+* Description : Enables or disables the specified CAN interrupts.
+* Input : - CAN_IT: specifies the CAN interrupt sources to be enabled or
+* disabled.
+* This parameter can be: CAN_IT_TME, CAN_IT_FMP0, CAN_IT_FF0,
+* CAN_IT_FOV0, CAN_IT_FMP1, CAN_IT_FF1,
+* CAN_IT_FOV1, CAN_IT_EWG, CAN_IT_EPV,
+* CAN_IT_LEC, CAN_IT_ERR, CAN_IT_WKU or
+* CAN_IT_SLK.
+* - NewState: new state of the CAN interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_ITConfig(u32 CAN_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_CAN_ITConfig(CAN_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected CAN interrupt */
+ CAN->IER |= CAN_IT;
+ }
+ else
+ {
+ /* Disable the selected CAN interrupt */
+ CAN->IER &= ~CAN_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : CAN_Transmit
+* Description : Initiates the transmission of a message.
+* Input : TxMessage: pointer to a structure which contains CAN Id, CAN
+* DLC and CAN datas.
+* Output : None.
+* Return : The number of the mailbox that is used for transmission
+* or CAN_NO_MB if there is no empty mailbox.
+*******************************************************************************/
+u8 CAN_Transmit(CanTxMsg* TxMessage)
+{
+ u8 TransmitMailbox = 0;
+
+ /* Check the parameters */
+ assert_param(IS_CAN_STDID(TxMessage->StdId));
+ assert_param(IS_CAN_EXTID(TxMessage->StdId));
+ assert_param(IS_CAN_IDTYPE(TxMessage->IDE));
+ assert_param(IS_CAN_RTR(TxMessage->RTR));
+ assert_param(IS_CAN_DLC(TxMessage->DLC));
+
+ /* Select one empty transmit mailbox */
+ if ((CAN->TSR&CAN_TSR_TME0) == CAN_TSR_TME0)
+ {
+ TransmitMailbox = 0;
+ }
+ else if ((CAN->TSR&CAN_TSR_TME1) == CAN_TSR_TME1)
+ {
+ TransmitMailbox = 1;
+ }
+ else if ((CAN->TSR&CAN_TSR_TME2) == CAN_TSR_TME2)
+ {
+ TransmitMailbox = 2;
+ }
+ else
+ {
+ TransmitMailbox = CAN_NO_MB;
+ }
+
+ if (TransmitMailbox != CAN_NO_MB)
+ {
+ /* Set up the Id */
+ CAN->sTxMailBox[TransmitMailbox].TIR &= CAN_TMIDxR_TXRQ;
+ if (TxMessage->IDE == CAN_ID_STD)
+ {
+ TxMessage->StdId &= (u32)0x000007FF;
+ TxMessage->StdId = TxMessage->StdId << 21;
+
+ CAN->sTxMailBox[TransmitMailbox].TIR |= (TxMessage->StdId | TxMessage->IDE |
+ TxMessage->RTR);
+ }
+ else
+ {
+ TxMessage->ExtId &= (u32)0x1FFFFFFF;
+ TxMessage->ExtId <<= 3;
+
+ CAN->sTxMailBox[TransmitMailbox].TIR |= (TxMessage->ExtId | TxMessage->IDE |
+ TxMessage->RTR);
+ }
+
+ /* Set up the DLC */
+ TxMessage->DLC &= (u8)0x0000000F;
+ CAN->sTxMailBox[TransmitMailbox].TDTR &= (u32)0xFFFFFFF0;
+ CAN->sTxMailBox[TransmitMailbox].TDTR |= TxMessage->DLC;
+
+ /* Set up the data field */
+ CAN->sTxMailBox[TransmitMailbox].TDLR = (((u32)TxMessage->Data[3] << 24) |
+ ((u32)TxMessage->Data[2] << 16) |
+ ((u32)TxMessage->Data[1] << 8) |
+ ((u32)TxMessage->Data[0]));
+ CAN->sTxMailBox[TransmitMailbox].TDHR = (((u32)TxMessage->Data[7] << 24) |
+ ((u32)TxMessage->Data[6] << 16) |
+ ((u32)TxMessage->Data[5] << 8) |
+ ((u32)TxMessage->Data[4]));
+
+ /* Request transmission */
+ CAN->sTxMailBox[TransmitMailbox].TIR |= CAN_TMIDxR_TXRQ;
+ }
+
+ return TransmitMailbox;
+}
+
+/*******************************************************************************
+* Function Name : CAN_TransmitStatus
+* Description : Checks the transmission of a message.
+* Input : TransmitMailbox: the number of the mailbox that is used for
+* transmission.
+* Output : None.
+* Return : CANTXOK if the CAN driver transmits the message, CANTXFAILED
+* in an other case.
+*******************************************************************************/
+u8 CAN_TransmitStatus(u8 TransmitMailbox)
+{
+ /* RQCP, TXOK and TME bits */
+ u8 State = 0;
+
+ /* Check the parameters */
+ assert_param(IS_CAN_TRANSMITMAILBOX(TransmitMailbox));
+
+ switch (TransmitMailbox)
+ {
+ case (0): State |= (u8)((CAN->TSR & CAN_TSR_RQCP0) << 2);
+ State |= (u8)((CAN->TSR & CAN_TSR_TXOK0) >> 0);
+ State |= (u8)((CAN->TSR & CAN_TSR_TME0) >> 26);
+ break;
+ case (1): State |= (u8)((CAN->TSR & CAN_TSR_RQCP1) >> 6);
+ State |= (u8)((CAN->TSR & CAN_TSR_TXOK1) >> 8);
+ State |= (u8)((CAN->TSR & CAN_TSR_TME1) >> 27);
+ break;
+ case (2): State |= (u8)((CAN->TSR & CAN_TSR_RQCP2) >> 14);
+ State |= (u8)((CAN->TSR & CAN_TSR_TXOK2) >> 16);
+ State |= (u8)((CAN->TSR & CAN_TSR_TME2) >> 28);
+ break;
+ default:
+ State = CANTXFAILED;
+ break;
+ }
+
+ switch (State)
+ {
+ /* transmit pending */
+ case (0x0): State = CANTXPENDING;
+ break;
+ /* transmit failed */
+ case (0x5): State = CANTXFAILED;
+ break;
+ /* transmit succedeed */
+ case (0x7): State = CANTXOK;
+ break;
+ default:
+ State = CANTXFAILED;
+ break;
+ }
+
+ return State;
+}
+
+/*******************************************************************************
+* Function Name : CAN_CancelTransmit
+* Description : Cancels a transmit request.
+* Input : Mailbox number.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_CancelTransmit(u8 Mailbox)
+{
+ /* Check the parameters */
+ assert_param(IS_CAN_TRANSMITMAILBOX(Mailbox));
+
+ /* abort transmission */
+ switch (Mailbox)
+ {
+ case (0): CAN->TSR |= CAN_TSR_ABRQ0;
+ break;
+ case (1): CAN->TSR |= CAN_TSR_ABRQ1;
+ break;
+ case (2): CAN->TSR |= CAN_TSR_ABRQ2;
+ break;
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : CAN_FIFORelease
+* Description : Releases a FIFO.
+* Input : FIFONumber: FIFO to release, CAN_FIFO0 or CAN_FIFO1.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_FIFORelease(u8 FIFONumber)
+{
+ /* Check the parameters */
+ assert_param(IS_CAN_FIFO(FIFONumber));
+
+ /* Release FIFO0 */
+ if (FIFONumber == CAN_FIFO0)
+ {
+ CAN->RF0R = CAN_RF0R_RFOM0;
+ }
+ /* Release FIFO1 */
+ else /* FIFONumber == CAN_FIFO1 */
+ {
+ CAN->RF1R = CAN_RF1R_RFOM1;
+ }
+}
+
+/*******************************************************************************
+* Function Name : CAN_MessagePending
+* Description : Returns the number of pending messages.
+* Input : FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1.
+* Output : None.
+* Return : NbMessage which is the number of pending message.
+*******************************************************************************/
+u8 CAN_MessagePending(u8 FIFONumber)
+{
+ u8 MessagePending=0;
+
+ /* Check the parameters */
+ assert_param(IS_CAN_FIFO(FIFONumber));
+
+ if (FIFONumber == CAN_FIFO0)
+ {
+ MessagePending = (u8)(CAN->RF0R&(u32)0x03);
+ }
+ else if (FIFONumber == CAN_FIFO1)
+ {
+ MessagePending = (u8)(CAN->RF1R&(u32)0x03);
+ }
+ else
+ {
+ MessagePending = 0;
+ }
+ return MessagePending;
+}
+
+/*******************************************************************************
+* Function Name : CAN_Receive
+* Description : Receives a message.
+* Input : FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1.
+* Output : RxMessage: pointer to a structure which contains CAN Id,
+* CAN DLC, CAN datas and FMI number.
+* Return : None.
+*******************************************************************************/
+void CAN_Receive(u8 FIFONumber, CanRxMsg* RxMessage)
+{
+ /* Check the parameters */
+ assert_param(IS_CAN_FIFO(FIFONumber));
+
+ /* Get the Id */
+ RxMessage->IDE = (u8)0x04 & CAN->sFIFOMailBox[FIFONumber].RIR;
+ if (RxMessage->IDE == CAN_ID_STD)
+ {
+ RxMessage->StdId = (u32)0x000007FF & (CAN->sFIFOMailBox[FIFONumber].RIR >> 21);
+ }
+ else
+ {
+ RxMessage->ExtId = (u32)0x1FFFFFFF & (CAN->sFIFOMailBox[FIFONumber].RIR >> 3);
+ }
+
+ RxMessage->RTR = (u8)0x02 & CAN->sFIFOMailBox[FIFONumber].RIR;
+
+ /* Get the DLC */
+ RxMessage->DLC = (u8)0x0F & CAN->sFIFOMailBox[FIFONumber].RDTR;
+
+ /* Get the FMI */
+ RxMessage->FMI = (u8)0xFF & (CAN->sFIFOMailBox[FIFONumber].RDTR >> 8);
+
+ /* Get the data field */
+ RxMessage->Data[0] = (u8)0xFF & CAN->sFIFOMailBox[FIFONumber].RDLR;
+ RxMessage->Data[1] = (u8)0xFF & (CAN->sFIFOMailBox[FIFONumber].RDLR >> 8);
+ RxMessage->Data[2] = (u8)0xFF & (CAN->sFIFOMailBox[FIFONumber].RDLR >> 16);
+ RxMessage->Data[3] = (u8)0xFF & (CAN->sFIFOMailBox[FIFONumber].RDLR >> 24);
+
+ RxMessage->Data[4] = (u8)0xFF & CAN->sFIFOMailBox[FIFONumber].RDHR;
+ RxMessage->Data[5] = (u8)0xFF & (CAN->sFIFOMailBox[FIFONumber].RDHR >> 8);
+ RxMessage->Data[6] = (u8)0xFF & (CAN->sFIFOMailBox[FIFONumber].RDHR >> 16);
+ RxMessage->Data[7] = (u8)0xFF & (CAN->sFIFOMailBox[FIFONumber].RDHR >> 24);
+
+ /* Release the FIFO */
+ CAN_FIFORelease(FIFONumber);
+}
+
+/*******************************************************************************
+* Function Name : CAN_Sleep
+* Description : Enters the low power mode.
+* Input : None.
+* Output : None.
+* Return : CANSLEEPOK if sleep entered, CANSLEEPFAILED in an other case.
+*******************************************************************************/
+u8 CAN_Sleep(void)
+{
+ u8 SleepStatus = 0;
+
+ /* Sleep mode entering request */
+ CAN->MCR |= CAN_MCR_SLEEP;
+ SleepStatus = CANSLEEPOK;
+
+ /* Sleep mode status */
+ if ((CAN->MCR&CAN_MCR_SLEEP) == 0)
+ {
+ /* Sleep mode not entered */
+ SleepStatus = CANSLEEPFAILED;
+ }
+
+ /* At this step, sleep mode status */
+ return SleepStatus;
+}
+
+/*******************************************************************************
+* Function Name : CAN_WakeUp
+* Description : Wakes the CAN up.
+* Input : None.
+* Output : None.
+* Return : CANWAKEUPOK if sleep mode left, CANWAKEUPFAILED in an other
+* case.
+*******************************************************************************/
+u8 CAN_WakeUp(void)
+{
+ u8 WakeUpStatus = 0;
+
+ /* Wake up request */
+ CAN->MCR &= ~CAN_MCR_SLEEP;
+ WakeUpStatus = CANWAKEUPFAILED;
+
+ /* Sleep mode status */
+ if ((CAN->MCR&CAN_MCR_SLEEP) == 0)
+ {
+ /* Sleep mode exited */
+ WakeUpStatus = CANWAKEUPOK;
+ }
+
+ /* At this step, sleep mode status */
+ return WakeUpStatus;
+}
+
+/*******************************************************************************
+* Function Name : CAN_GetFlagStatus
+* Description : Checks whether the specified CAN flag is set or not.
+* Input : CAN_FLAG: specifies the flag to check.
+* This parameter can be: CAN_FLAG_EWG, CAN_FLAG_EPV or
+* CAN_FLAG_BOF.
+* Output : None.
+* Return : The new state of CAN_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus CAN_GetFlagStatus(u32 CAN_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_CAN_FLAG(CAN_FLAG));
+
+ /* Check the status of the specified CAN flag */
+ if ((CAN->ESR & CAN_FLAG) != (u32)RESET)
+ {
+ /* CAN_FLAG is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* CAN_FLAG is reset */
+ bitstatus = RESET;
+ }
+ /* Return the CAN_FLAG status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : CAN_ClearFlag
+* Description : Clears the CAN's pending flags.
+* Input : CAN_FLAG: specifies the flag to clear.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_ClearFlag(u32 CAN_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_CAN_FLAG(CAN_FLAG));
+
+ /* Clear the selected CAN flags */
+ CAN->ESR &= ~CAN_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : CAN_GetITStatus
+* Description : Checks whether the specified CAN interrupt has occurred or
+* not.
+* Input : CAN_IT: specifies the CAN interrupt source to check.
+* This parameter can be: CAN_IT_RQCP0, CAN_IT_RQCP1, CAN_IT_RQCP2,
+* CAN_IT_FF0, CAN_IT_FOV0, CAN_IT_FF1,
+* CAN_IT_FOV1, CAN_IT_EWG, CAN_IT_EPV,
+* CAN_IT_BOF, CAN_IT_WKU or CAN_IT_SLK.
+* Output : None.
+* Return : The new state of CAN_IT (SET or RESET).
+*******************************************************************************/
+ITStatus CAN_GetITStatus(u32 CAN_IT)
+{
+ ITStatus pendingbitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_CAN_ITStatus(CAN_IT));
+
+ switch (CAN_IT)
+ {
+ case CAN_IT_RQCP0:
+ pendingbitstatus = CheckITStatus(CAN->TSR, CAN_TSR_RQCP0);
+ break;
+ case CAN_IT_RQCP1:
+ pendingbitstatus = CheckITStatus(CAN->TSR, CAN_TSR_RQCP1);
+ break;
+ case CAN_IT_RQCP2:
+ pendingbitstatus = CheckITStatus(CAN->TSR, CAN_TSR_RQCP2);
+ break;
+ case CAN_IT_FF0:
+ pendingbitstatus = CheckITStatus(CAN->RF0R, CAN_RF0R_FULL0);
+ break;
+ case CAN_IT_FOV0:
+ pendingbitstatus = CheckITStatus(CAN->RF0R, CAN_RF0R_FOVR0);
+ break;
+ case CAN_IT_FF1:
+ pendingbitstatus = CheckITStatus(CAN->RF1R, CAN_RF1R_FULL1);
+ break;
+ case CAN_IT_FOV1:
+ pendingbitstatus = CheckITStatus(CAN->RF1R, CAN_RF1R_FOVR1);
+ break;
+ case CAN_IT_EWG:
+ pendingbitstatus = CheckITStatus(CAN->ESR, CAN_ESR_EWGF);
+ break;
+ case CAN_IT_EPV:
+ pendingbitstatus = CheckITStatus(CAN->ESR, CAN_ESR_EPVF);
+ break;
+ case CAN_IT_BOF:
+ pendingbitstatus = CheckITStatus(CAN->ESR, CAN_ESR_BOFF);
+ break;
+ case CAN_IT_SLK:
+ pendingbitstatus = CheckITStatus(CAN->MSR, CAN_MSR_SLAKI);
+ break;
+ case CAN_IT_WKU:
+ pendingbitstatus = CheckITStatus(CAN->MSR, CAN_MSR_WKUI);
+ break;
+
+ default :
+ pendingbitstatus = RESET;
+ break;
+ }
+
+ /* Return the CAN_IT status */
+ return pendingbitstatus;
+}
+
+/*******************************************************************************
+* Function Name : CAN_ClearITPendingBit
+* Description : Clears the CAN’s interrupt pending bits.
+* Input : CAN_IT: specifies the interrupt pending bit to clear.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_ClearITPendingBit(u32 CAN_IT)
+{
+ /* Check the parameters */
+ assert_param(IS_CAN_ITStatus(CAN_IT));
+
+ switch (CAN_IT)
+ {
+ case CAN_IT_RQCP0:
+ CAN->TSR = CAN_TSR_RQCP0; /* rc_w1*/
+ break;
+ case CAN_IT_RQCP1:
+ CAN->TSR = CAN_TSR_RQCP1; /* rc_w1*/
+ break;
+ case CAN_IT_RQCP2:
+ CAN->TSR = CAN_TSR_RQCP2; /* rc_w1*/
+ break;
+ case CAN_IT_FF0:
+ CAN->RF0R = CAN_RF0R_FULL0; /* rc_w1*/
+ break;
+ case CAN_IT_FOV0:
+ CAN->RF0R = CAN_RF0R_FOVR0; /* rc_w1*/
+ break;
+ case CAN_IT_FF1:
+ CAN->RF1R = CAN_RF1R_FULL1; /* rc_w1*/
+ break;
+ case CAN_IT_FOV1:
+ CAN->RF1R = CAN_RF1R_FOVR1; /* rc_w1*/
+ break;
+ case CAN_IT_EWG:
+ CAN->ESR &= ~ CAN_ESR_EWGF; /* rw */
+ break;
+ case CAN_IT_EPV:
+ CAN->ESR &= ~ CAN_ESR_EPVF; /* rw */
+ break;
+ case CAN_IT_BOF:
+ CAN->ESR &= ~ CAN_ESR_BOFF; /* rw */
+ break;
+ case CAN_IT_WKU:
+ CAN->MSR = CAN_MSR_WKUI; /* rc_w1*/
+ break;
+ case CAN_IT_SLK:
+ CAN->MSR = CAN_MSR_SLAKI; /* rc_w1*/
+ break;
+ default :
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : CheckITStatus
+* Description : Checks whether the CAN interrupt has occurred or not.
+* Input : CAN_Reg: specifies the CAN interrupt register to check.
+* It_Bit: specifies the interrupt source bit to check.
+* Output : None.
+* Return : The new state of the CAN Interrupt (SET or RESET).
+*******************************************************************************/
+static ITStatus CheckITStatus(u32 CAN_Reg, u32 It_Bit)
+{
+ ITStatus pendingbitstatus = RESET;
+
+ if ((CAN_Reg & It_Bit) != (u32)RESET)
+ {
+ /* CAN_IT is set */
+ pendingbitstatus = SET;
+ }
+ else
+ {
+ /* CAN_IT is reset */
+ pendingbitstatus = RESET;
+ }
+
+ return pendingbitstatus;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_crc.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_crc.c new file mode 100755 index 0000000..9ba3089 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_crc.c @@ -0,0 +1,114 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_crc.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the CRC firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_crc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* CR register bit mask */
+#define CR_RESET_Set ((u32)0x00000001)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : CRC_ResetDR
+* Description : Resets the CRC Data register (DR).
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CRC_ResetDR(void)
+{
+ /* Reset CRC generator */
+ CRC->CR = CR_RESET_Set;
+}
+
+/*******************************************************************************
+* Function Name : CRC_CalcCRC
+* Description : Computes the 32-bit CRC of a given data word(32-bit).
+* Input : - Data: data word(32-bit) to compute its CRC
+* Output : None
+* Return : 32-bit CRC
+*******************************************************************************/
+u32 CRC_CalcCRC(u32 Data)
+{
+ CRC->DR = Data;
+
+ return (CRC->DR);
+}
+
+/*******************************************************************************
+* Function Name : CRC_CalcBlockCRC
+* Description : Computes the 32-bit CRC of a given buffer of data word(32-bit).
+* Input : - pBuffer: pointer to the buffer containing the data to be
+* computed
+* - BufferLength: length of the buffer to be computed
+* Output : None
+* Return : 32-bit CRC
+*******************************************************************************/
+u32 CRC_CalcBlockCRC(u32 pBuffer[], u32 BufferLength)
+{
+ u32 index = 0;
+
+ for(index = 0; index < BufferLength; index++)
+ {
+ CRC->DR = pBuffer[index];
+ }
+
+ return (CRC->DR);
+}
+
+/*******************************************************************************
+* Function Name : CRC_GetCRC
+* Description : Returns the current CRC value.
+* Input : None
+* Output : None
+* Return : 32-bit CRC
+*******************************************************************************/
+u32 CRC_GetCRC(void)
+{
+ return (CRC->DR);
+}
+
+/*******************************************************************************
+* Function Name : CRC_SetIDRegister
+* Description : Stores a 8-bit data in the Independent Data(ID) register.
+* Input : - IDValue: 8-bit value to be stored in the ID register
+* Output : None
+* Return : None
+*******************************************************************************/
+void CRC_SetIDRegister(u8 IDValue)
+{
+ CRC->IDR = IDValue;
+}
+
+/*******************************************************************************
+* Function Name : CRC_GetIDRegister
+* Description : Returns the 8-bit data stored in the Independent Data(ID) register
+* Input : None
+* Output : None
+* Return : 8-bit value of the ID register
+*******************************************************************************/
+u8 CRC_GetIDRegister(void)
+{
+ return (CRC->IDR);
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_dac.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_dac.c new file mode 100755 index 0000000..12b1c92 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_dac.c @@ -0,0 +1,389 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_dac.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the DAC firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_dac.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* DAC EN mask */
+#define CR_EN_Set ((u32)0x00000001)
+
+/* DAC DMAEN mask */
+#define CR_DMAEN_Set ((u32)0x00001000)
+
+/* CR register Mask */
+#define CR_CLEAR_Mask ((u32)0x00000FFE)
+
+/* DAC SWTRIG mask */
+#define SWTRIGR_SWTRIG_Set ((u32)0x00000001)
+
+/* DAC Dual Channels SWTRIG masks */
+#define DUAL_SWTRIG_Set ((u32)0x00000003)
+#define DUAL_SWTRIG_Reset ((u32)0xFFFFFFFC)
+
+/* DHR registers offsets */
+#define DHR12R1_Offset ((u32)0x00000008)
+#define DHR12R2_Offset ((u32)0x00000014)
+#define DHR12RD_Offset ((u32)0x00000020)
+
+/* DOR register offset */
+#define DOR_Offset ((u32)0x0000002C)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : DAC_DeInit
+* Description : Deinitializes the DAC peripheral registers to their default
+* reset values.
+* Input : None.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_DeInit(void)
+{
+ /* Enable DAC reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, ENABLE);
+ /* Release DAC from reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, DISABLE);
+}
+
+/*******************************************************************************
+* Function Name : DAC_Init
+* Description : Initializes the DAC peripheral according to the specified
+* parameters in the DAC_InitStruct.
+* Input : - DAC_Channel: the selected DAC channel.
+* This parameter can be one of the following values:
+* - DAC_Channel_1: DAC Channel1 selected
+* - DAC_Channel_2: DAC Channel2 selected
+* - DAC_InitStruct: pointer to a DAC_InitTypeDef structure that
+* contains the configuration information for the specified
+* DAC channel.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_Init(u32 DAC_Channel, DAC_InitTypeDef* DAC_InitStruct)
+{
+ u32 tmpreg1 = 0, tmpreg2 = 0;
+
+ /* Check the DAC parameters */
+ assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger));
+ assert_param(IS_DAC_GENERATE_WAVE(DAC_InitStruct->DAC_WaveGeneration));
+ assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude));
+ assert_param(IS_DAC_OUTPUT_BUFFER_STATE(DAC_InitStruct->DAC_OutputBuffer));
+
+/*---------------------------- DAC CR Configuration --------------------------*/
+ /* Get the DAC CR value */
+ tmpreg1 = DAC->CR;
+ /* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */
+ tmpreg1 &= ~(CR_CLEAR_Mask << DAC_Channel);
+ /* Configure for the selected DAC channel: buffer output, trigger, wave genration,
+ mask/amplitude for wave genration */
+ /* Set TSELx and TENx bits according to DAC_Trigger value */
+ /* Set WAVEx bits according to DAC_WaveGeneration value */
+ /* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */
+ /* Set BOFFx bit according to DAC_OutputBuffer value */
+ tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration |
+ DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | DAC_InitStruct->DAC_OutputBuffer);
+ /* Calculate CR register value depending on DAC_Channel */
+ tmpreg1 |= tmpreg2 << DAC_Channel;
+ /* Write to DAC CR */
+ DAC->CR = tmpreg1;
+}
+
+/*******************************************************************************
+* Function Name : DAC_StructInit
+* Description : Fills each DAC_InitStruct member with its default value.
+* Input : - DAC_InitStruct : pointer to a DAC_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct)
+{
+/*--------------- Reset DAC init structure parameters values -----------------*/
+ /* Initialize the DAC_Trigger member */
+ DAC_InitStruct->DAC_Trigger = DAC_Trigger_None;
+
+ /* Initialize the DAC_WaveGeneration member */
+ DAC_InitStruct->DAC_WaveGeneration = DAC_WaveGeneration_None;
+
+ /* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */
+ DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0;
+
+ /* Initialize the DAC_OutputBuffer member */
+ DAC_InitStruct->DAC_OutputBuffer = DAC_OutputBuffer_Enable;
+}
+
+/*******************************************************************************
+* Function Name : DAC_Cmd
+* Description : Enables or disables the specified DAC channel.
+* Input - DAC_Channel: the selected DAC channel.
+* This parameter can be one of the following values:
+* - DAC_Channel_1: DAC Channel1 selected
+* - DAC_Channel_2: DAC Channel2 selected
+* - NewState: new state of the DAC channel.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_Cmd(u32 DAC_Channel, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_DAC_CHANNEL(DAC_Channel));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected DAC channel */
+ DAC->CR |= CR_EN_Set << DAC_Channel;
+ }
+ else
+ {
+ /* Disable the selected DAC channel */
+ DAC->CR &= ~(CR_EN_Set << DAC_Channel);
+ }
+}
+
+/*******************************************************************************
+* Function Name : DAC_DMACmd
+* Description : Enables or disables the specified DAC channel DMA request.
+* Input - DAC_Channel: the selected DAC channel.
+* This parameter can be one of the following values:
+* - DAC_Channel_1: DAC Channel1 selected
+* - DAC_Channel_2: DAC Channel2 selected
+* - NewState: new state of the selected DAC channel DMA request.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_DMACmd(u32 DAC_Channel, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_DAC_CHANNEL(DAC_Channel));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected DAC channel DMA request */
+ DAC->CR |= CR_DMAEN_Set << DAC_Channel;
+ }
+ else
+ {
+ /* Disable the selected DAC channel DMA request */
+ DAC->CR &= ~(CR_DMAEN_Set << DAC_Channel);
+ }
+}
+
+/*******************************************************************************
+* Function Name : DAC_SoftwareTriggerCmd
+* Description : Enables or disables the selected DAC channel software trigger.
+* Input - DAC_Channel: the selected DAC channel.
+* This parameter can be one of the following values:
+* - DAC_Channel_1: DAC Channel1 selected
+* - DAC_Channel_2: DAC Channel2 selected
+* - NewState: new state of the selected DAC channel software trigger.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_SoftwareTriggerCmd(u32 DAC_Channel, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_DAC_CHANNEL(DAC_Channel));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable software trigger for the selected DAC channel */
+ DAC->SWTRIGR |= SWTRIGR_SWTRIG_Set << (DAC_Channel >> 4);
+ }
+ else
+ {
+ /* Disable software trigger for the selected DAC channel */
+ DAC->SWTRIGR &= ~(SWTRIGR_SWTRIG_Set << (DAC_Channel >> 4));
+ }
+}
+
+/*******************************************************************************
+* Function Name : DAC_DualSoftwareTriggerCmd
+* Description : Enables or disables simultaneously the two DAC channels software
+* triggers.
+* Input - NewState: new state of the DAC channels software triggers.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_DualSoftwareTriggerCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable software trigger for both DAC channels */
+ DAC->SWTRIGR |= DUAL_SWTRIG_Set ;
+ }
+ else
+ {
+ /* Disable software trigger for both DAC channels */
+ DAC->SWTRIGR &= DUAL_SWTRIG_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : DAC_WaveGenerationCmd
+* Description : Enables or disables the selected DAC channel wave generation.
+* Input - DAC_Channel: the selected DAC channel.
+* This parameter can be one of the following values:
+* - DAC_Channel_1: DAC Channel1 selected
+* - DAC_Channel_2: DAC Channel2 selected
+* - DAC_Wave: Specifies the wave type to enable or disable.
+* This parameter can be one of the following values:
+* - DAC_Wave_Noise: noise wave generation
+* - DAC_Wave_Triangle: triangle wave generation
+* - NewState: new state of the selected DAC channel wave generation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_WaveGenerationCmd(u32 DAC_Channel, u32 DAC_Wave, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_DAC_CHANNEL(DAC_Channel));
+ assert_param(IS_DAC_WAVE(DAC_Wave));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected wave generation for the selected DAC channel */
+ DAC->CR |= DAC_Wave << DAC_Channel;
+ }
+ else
+ {
+ /* Disable the selected wave generation for the selected DAC channel */
+ DAC->CR &= ~(DAC_Wave << DAC_Channel);
+ }
+}
+
+/*******************************************************************************
+* Function Name : DAC_SetChannel1Data
+* Description : Set the specified data holding register value for DAC channel1.
+* Input : - DAC_Align: Specifies the data alignement for DAC channel1.
+* This parameter can be one of the following values:
+* - DAC_Align_8b_R: 8bit right data alignement selected
+* - DAC_Align_12b_L: 12bit left data alignement selected
+* - DAC_Align_12b_R: 12bit right data alignement selected
+* - Data : Data to be loaded in the selected data holding
+* register.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_SetChannel1Data(u32 DAC_Align, u16 Data)
+{
+ /* Check the parameters */
+ assert_param(IS_DAC_ALIGN(DAC_Align));
+ assert_param(IS_DAC_DATA(Data));
+
+ /* Set the DAC channel1 selected data holding register */
+ *((vu32 *)(DAC_BASE + DHR12R1_Offset + DAC_Align)) = (u32)Data;
+}
+
+/*******************************************************************************
+* Function Name : DAC_SetChannel2Data
+* Description : Set the specified data holding register value for DAC channel2.
+* Input : - DAC_Align: Specifies the data alignement for DAC channel2.
+* This parameter can be one of the following values:
+* - DAC_Align_8b_R: 8bit right data alignement selected
+* - DAC_Align_12b_L: 12bit left data alignement selected
+* - DAC_Align_12b_R: 12bit right data alignement selected
+* - Data : Data to be loaded in the selected data holding
+* register.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_SetChannel2Data(u32 DAC_Align, u16 Data)
+{
+ /* Check the parameters */
+ assert_param(IS_DAC_ALIGN(DAC_Align));
+ assert_param(IS_DAC_DATA(Data));
+
+ /* Set the DAC channel2 selected data holding register */
+ *((vu32 *)(DAC_BASE + DHR12R2_Offset + DAC_Align)) = (u32)Data;
+}
+
+/*******************************************************************************
+* Function Name : DAC_SetDualChannelData
+* Description : Set the specified data holding register value for dual channel
+* DAC.
+* Input : - DAC_Align: Specifies the data alignement for dual channel DAC.
+* This parameter can be one of the following values:
+* - DAC_Align_8b_R: 8bit right data alignement selected
+* - DAC_Align_12b_L: 12bit left data alignement selected
+* - DAC_Align_12b_R: 12bit right data alignement selected
+* - Data2: Data for DAC Channel2 to be loaded in the selected data
+* holding register.
+* - Data1: Data for DAC Channel1 to be loaded in the selected data
+* holding register.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_SetDualChannelData(u32 DAC_Align, u16 Data2, u16 Data1)
+{
+ u32 Data = 0;
+
+ /* Check the parameters */
+ assert_param(IS_DAC_ALIGN(DAC_Align));
+ assert_param(IS_DAC_DATA(Data1));
+ assert_param(IS_DAC_DATA(Data2));
+
+ /* Calculate and set dual DAC data holding register value */
+ if (DAC_Align == DAC_Align_8b_R)
+ {
+ Data = ((u32)Data2 << 8) | Data1;
+ }
+ else
+ {
+ Data = ((u32)Data2 << 16) | Data1;
+ }
+
+ /* Set the dual DAC selected data holding register */
+ *((vu32 *)(DAC_BASE + DHR12RD_Offset + DAC_Align)) = Data;
+}
+
+/*******************************************************************************
+* Function Name : DAC_GetDataOutputValue
+* Description : Returns the last data output value of the selected DAC cahnnel.
+* Input - DAC_Channel: the selected DAC channel.
+* This parameter can be one of the following values:
+* - DAC_Channel_1: DAC Channel1 selected
+* - DAC_Channel_2: DAC Channel2 selected
+* Output : None
+* Return : The selected DAC channel data output value.
+*******************************************************************************/
+u16 DAC_GetDataOutputValue(u32 DAC_Channel)
+{
+ /* Check the parameters */
+ assert_param(IS_DAC_CHANNEL(DAC_Channel));
+
+ /* Returns the DAC channel data output register value */
+ return (u16) (*(vu32*)(DAC_BASE + DOR_Offset + ((u32)DAC_Channel >> 2)));
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_dbgmcu.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_dbgmcu.c new file mode 100755 index 0000000..1e0dd54 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_dbgmcu.c @@ -0,0 +1,97 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_dbgmcu.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the DBGMCU firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_dbgmcu.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define IDCODE_DEVID_Mask ((u32)0x00000FFF)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : DBGMCU_GetREVID
+* Description : Returns the device revision identifier.
+* Input : None
+* Output : None
+* Return : Device revision identifier
+*******************************************************************************/
+u32 DBGMCU_GetREVID(void)
+{
+ return(DBGMCU->IDCODE >> 16);
+}
+
+/*******************************************************************************
+* Function Name : DBGMCU_GetDEVID
+* Description : Returns the device identifier.
+* Input : None
+* Output : None
+* Return : Device identifier
+*******************************************************************************/
+u32 DBGMCU_GetDEVID(void)
+{
+ return(DBGMCU->IDCODE & IDCODE_DEVID_Mask);
+}
+
+/*******************************************************************************
+* Function Name : DBGMCU_Config
+* Description : Configures the specified peripheral and low power mode behavior
+* when the MCU under Debug mode.
+* Input : - DBGMCU_Periph: specifies the peripheral and low power mode.
+* This parameter can be any combination of the following values:
+* - DBGMCU_SLEEP: Keep debugger connection during SLEEP mode
+* - DBGMCU_STOP: Keep debugger connection during STOP mode
+* - DBGMCU_STANDBY: Keep debugger connection during STANDBY mode
+* - DBGMCU_IWDG_STOP: Debug IWDG stopped when Core is halted
+* - DBGMCU_WWDG_STOP: Debug WWDG stopped when Core is halted
+* - DBGMCU_TIM1_STOP: TIM1 counter stopped when Core is halted
+* - DBGMCU_TIM2_STOP: TIM2 counter stopped when Core is halted
+* - DBGMCU_TIM3_STOP: TIM3 counter stopped when Core is halted
+* - DBGMCU_TIM4_STOP: TIM4 counter stopped when Core is halted
+* - DBGMCU_CAN_STOP: Debug CAN stopped when Core is halted
+* - DBGMCU_I2C1_SMBUS_TIMEOUT: I2C1 SMBUS timeout mode stopped
+* when Core is halted
+* - DBGMCU_I2C2_SMBUS_TIMEOUT: I2C2 SMBUS timeout mode stopped
+* when Core is halted
+* - DBGMCU_TIM5_STOP: TIM5 counter stopped when Core is halted
+* - DBGMCU_TIM6_STOP: TIM6 counter stopped when Core is halted
+* - DBGMCU_TIM7_STOP: TIM7 counter stopped when Core is halted
+* - DBGMCU_TIM8_STOP: TIM8 counter stopped when Core is halted
+* - NewState: new state of the specified peripheral in Debug mode.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DBGMCU_Config(u32 DBGMCU_Periph, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_DBGMCU_PERIPH(DBGMCU_Periph));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ DBGMCU->CR |= DBGMCU_Periph;
+ }
+ else
+ {
+ DBGMCU->CR &= ~DBGMCU_Periph;
+ }
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_dma.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_dma.c new file mode 100755 index 0000000..3cf55c8 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_dma.c @@ -0,0 +1,678 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_dma.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the DMA firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_dma.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* DMA ENABLE mask */
+#define CCR_ENABLE_Set ((u32)0x00000001)
+#define CCR_ENABLE_Reset ((u32)0xFFFFFFFE)
+
+/* DMA1 Channelx interrupt pending bit masks */
+#define DMA1_Channel1_IT_Mask ((u32)0x0000000F)
+#define DMA1_Channel2_IT_Mask ((u32)0x000000F0)
+#define DMA1_Channel3_IT_Mask ((u32)0x00000F00)
+#define DMA1_Channel4_IT_Mask ((u32)0x0000F000)
+#define DMA1_Channel5_IT_Mask ((u32)0x000F0000)
+#define DMA1_Channel6_IT_Mask ((u32)0x00F00000)
+#define DMA1_Channel7_IT_Mask ((u32)0x0F000000)
+
+/* DMA2 Channelx interrupt pending bit masks */
+#define DMA2_Channel1_IT_Mask ((u32)0x0000000F)
+#define DMA2_Channel2_IT_Mask ((u32)0x000000F0)
+#define DMA2_Channel3_IT_Mask ((u32)0x00000F00)
+#define DMA2_Channel4_IT_Mask ((u32)0x0000F000)
+#define DMA2_Channel5_IT_Mask ((u32)0x000F0000)
+
+/* DMA2 FLAG mask */
+#define FLAG_Mask ((u32)0x10000000)
+
+/* DMA registers Masks */
+#define CCR_CLEAR_Mask ((u32)0xFFFF800F)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : DMA_DeInit
+* Description : Deinitializes the DMAy Channelx registers to their default reset
+* values.
+* Input : - DMAy_Channelx: where y can be 1 or 2 to select the DMA and
+* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the
+* DMA Channel.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx)
+{
+ /* Check the parameters */
+ assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+
+ /* Disable the selected DMAy Channelx */
+ DMAy_Channelx->CCR &= CCR_ENABLE_Reset;
+
+ /* Reset DMAy Channelx control register */
+ DMAy_Channelx->CCR = 0;
+
+ /* Reset DMAy Channelx remaining bytes register */
+ DMAy_Channelx->CNDTR = 0;
+
+ /* Reset DMAy Channelx peripheral address register */
+ DMAy_Channelx->CPAR = 0;
+
+ /* Reset DMAy Channelx memory address register */
+ DMAy_Channelx->CMAR = 0;
+
+ switch (*(u32*)&DMAy_Channelx)
+ {
+ case DMA1_Channel1_BASE:
+ /* Reset interrupt pending bits for DMA1 Channel1 */
+ DMA1->IFCR |= DMA1_Channel1_IT_Mask;
+ break;
+
+ case DMA1_Channel2_BASE:
+ /* Reset interrupt pending bits for DMA1 Channel2 */
+ DMA1->IFCR |= DMA1_Channel2_IT_Mask;
+ break;
+
+ case DMA1_Channel3_BASE:
+ /* Reset interrupt pending bits for DMA1 Channel3 */
+ DMA1->IFCR |= DMA1_Channel3_IT_Mask;
+ break;
+
+ case DMA1_Channel4_BASE:
+ /* Reset interrupt pending bits for DMA1 Channel4 */
+ DMA1->IFCR |= DMA1_Channel4_IT_Mask;
+ break;
+
+ case DMA1_Channel5_BASE:
+ /* Reset interrupt pending bits for DMA1 Channel5 */
+ DMA1->IFCR |= DMA1_Channel5_IT_Mask;
+ break;
+
+ case DMA1_Channel6_BASE:
+ /* Reset interrupt pending bits for DMA1 Channel6 */
+ DMA1->IFCR |= DMA1_Channel6_IT_Mask;
+ break;
+
+ case DMA1_Channel7_BASE:
+ /* Reset interrupt pending bits for DMA1 Channel7 */
+ DMA1->IFCR |= DMA1_Channel7_IT_Mask;
+ break;
+
+ case DMA2_Channel1_BASE:
+ /* Reset interrupt pending bits for DMA2 Channel1 */
+ DMA2->IFCR |= DMA2_Channel1_IT_Mask;
+ break;
+
+ case DMA2_Channel2_BASE:
+ /* Reset interrupt pending bits for DMA2 Channel2 */
+ DMA2->IFCR |= DMA2_Channel2_IT_Mask;
+ break;
+
+ case DMA2_Channel3_BASE:
+ /* Reset interrupt pending bits for DMA2 Channel3 */
+ DMA2->IFCR |= DMA2_Channel3_IT_Mask;
+ break;
+
+ case DMA2_Channel4_BASE:
+ /* Reset interrupt pending bits for DMA2 Channel4 */
+ DMA2->IFCR |= DMA2_Channel4_IT_Mask;
+ break;
+
+ case DMA2_Channel5_BASE:
+ /* Reset interrupt pending bits for DMA2 Channel5 */
+ DMA2->IFCR |= DMA2_Channel5_IT_Mask;
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : DMA_Init
+* Description : Initializes the DMAy Channelx according to the specified
+* parameters in the DMA_InitStruct.
+* Input : - DMAy_Channelx: where y can be 1 or 2 to select the DMA and
+* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the
+* DMA Channel.
+* - DMA_InitStruct: pointer to a DMA_InitTypeDef structure that
+* contains the configuration information for the specified
+* DMA Channel.
+* Output : None
+* Return : None
+******************************************************************************/
+void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+ assert_param(IS_DMA_DIR(DMA_InitStruct->DMA_DIR));
+ assert_param(IS_DMA_BUFFER_SIZE(DMA_InitStruct->DMA_BufferSize));
+ assert_param(IS_DMA_PERIPHERAL_INC_STATE(DMA_InitStruct->DMA_PeripheralInc));
+ assert_param(IS_DMA_MEMORY_INC_STATE(DMA_InitStruct->DMA_MemoryInc));
+ assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(DMA_InitStruct->DMA_PeripheralDataSize));
+ assert_param(IS_DMA_MEMORY_DATA_SIZE(DMA_InitStruct->DMA_MemoryDataSize));
+ assert_param(IS_DMA_MODE(DMA_InitStruct->DMA_Mode));
+ assert_param(IS_DMA_PRIORITY(DMA_InitStruct->DMA_Priority));
+ assert_param(IS_DMA_M2M_STATE(DMA_InitStruct->DMA_M2M));
+
+/*--------------------------- DMAy Channelx CCR Configuration -----------------*/
+ /* Get the DMAy_Channelx CCR value */
+ tmpreg = DMAy_Channelx->CCR;
+ /* Clear MEM2MEM, PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */
+ tmpreg &= CCR_CLEAR_Mask;
+ /* Configure DMAy Channelx: data transfer, data size, priority level and mode */
+ /* Set DIR bit according to DMA_DIR value */
+ /* Set CIRC bit according to DMA_Mode value */
+ /* Set PINC bit according to DMA_PeripheralInc value */
+ /* Set MINC bit according to DMA_MemoryInc value */
+ /* Set PSIZE bits according to DMA_PeripheralDataSize value */
+ /* Set MSIZE bits according to DMA_MemoryDataSize value */
+ /* Set PL bits according to DMA_Priority value */
+ /* Set the MEM2MEM bit according to DMA_M2M value */
+ tmpreg |= DMA_InitStruct->DMA_DIR | DMA_InitStruct->DMA_Mode |
+ DMA_InitStruct->DMA_PeripheralInc | DMA_InitStruct->DMA_MemoryInc |
+ DMA_InitStruct->DMA_PeripheralDataSize | DMA_InitStruct->DMA_MemoryDataSize |
+ DMA_InitStruct->DMA_Priority | DMA_InitStruct->DMA_M2M;
+ /* Write to DMAy Channelx CCR */
+ DMAy_Channelx->CCR = tmpreg;
+
+/*--------------------------- DMAy Channelx CNDTR Configuration ---------------*/
+ /* Write to DMAy Channelx CNDTR */
+ DMAy_Channelx->CNDTR = DMA_InitStruct->DMA_BufferSize;
+
+/*--------------------------- DMAy Channelx CPAR Configuration ----------------*/
+ /* Write to DMAy Channelx CPAR */
+ DMAy_Channelx->CPAR = DMA_InitStruct->DMA_PeripheralBaseAddr;
+
+/*--------------------------- DMAy Channelx CMAR Configuration ----------------*/
+ /* Write to DMAy Channelx CMAR */
+ DMAy_Channelx->CMAR = DMA_InitStruct->DMA_MemoryBaseAddr;
+}
+
+/*******************************************************************************
+* Function Name : DMA_StructInit
+* Description : Fills each DMA_InitStruct member with its default value.
+* Input : - DMA_InitStruct : pointer to a DMA_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct)
+{
+/*-------------- Reset DMA init structure parameters values ------------------*/
+ /* Initialize the DMA_PeripheralBaseAddr member */
+ DMA_InitStruct->DMA_PeripheralBaseAddr = 0;
+
+ /* Initialize the DMA_MemoryBaseAddr member */
+ DMA_InitStruct->DMA_MemoryBaseAddr = 0;
+
+ /* Initialize the DMA_DIR member */
+ DMA_InitStruct->DMA_DIR = DMA_DIR_PeripheralSRC;
+
+ /* Initialize the DMA_BufferSize member */
+ DMA_InitStruct->DMA_BufferSize = 0;
+
+ /* Initialize the DMA_PeripheralInc member */
+ DMA_InitStruct->DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+
+ /* Initialize the DMA_MemoryInc member */
+ DMA_InitStruct->DMA_MemoryInc = DMA_MemoryInc_Disable;
+
+ /* Initialize the DMA_PeripheralDataSize member */
+ DMA_InitStruct->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+
+ /* Initialize the DMA_MemoryDataSize member */
+ DMA_InitStruct->DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+
+ /* Initialize the DMA_Mode member */
+ DMA_InitStruct->DMA_Mode = DMA_Mode_Normal;
+
+ /* Initialize the DMA_Priority member */
+ DMA_InitStruct->DMA_Priority = DMA_Priority_Low;
+
+ /* Initialize the DMA_M2M member */
+ DMA_InitStruct->DMA_M2M = DMA_M2M_Disable;
+}
+
+/*******************************************************************************
+* Function Name : DMA_Cmd
+* Description : Enables or disables the specified DMAy Channelx.
+* Input : - DMAy_Channelx: where y can be 1 or 2 to select the DMA and
+* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the
+* DMA Channel.
+* - NewState: new state of the DMAy Channelx.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected DMAy Channelx */
+ DMAy_Channelx->CCR |= CCR_ENABLE_Set;
+ }
+ else
+ {
+ /* Disable the selected DMAy Channelx */
+ DMAy_Channelx->CCR &= CCR_ENABLE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : DMA_ITConfig
+* Description : Enables or disables the specified DMAy Channelx interrupts.
+* Input : - DMAy_Channelx: where y can be 1 or 2 to select the DMA and
+* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the
+* DMA Channel.
+* - DMA_IT: specifies the DMA interrupts sources to be enabled
+* or disabled.
+* This parameter can be any combination of the following values:
+* - DMA_IT_TC: Transfer complete interrupt mask
+* - DMA_IT_HT: Half transfer interrupt mask
+* - DMA_IT_TE: Transfer error interrupt mask
+* - NewState: new state of the specified DMA interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, u32 DMA_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+ assert_param(IS_DMA_CONFIG_IT(DMA_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected DMA interrupts */
+ DMAy_Channelx->CCR |= DMA_IT;
+ }
+ else
+ {
+ /* Disable the selected DMA interrupts */
+ DMAy_Channelx->CCR &= ~DMA_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : DMA_GetCurrDataCounter
+* Description : Returns the number of remaining data units in the current
+* DMAy Channelx transfer.
+* Input : - DMAy_Channelx: where y can be 1 or 2 to select the DMA and
+* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the
+* DMA Channel.
+* Output : None
+* Return : The number of remaining data units in the current DMAy Channelx
+* transfer.
+*******************************************************************************/
+u16 DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx)
+{
+ /* Check the parameters */
+ assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+
+ /* Return the number of remaining data units for DMAy Channelx */
+ return ((u16)(DMAy_Channelx->CNDTR));
+}
+
+/*******************************************************************************
+* Function Name : DMA_GetFlagStatus
+* Description : Checks whether the specified DMAy Channelx flag is set or not.
+* Input : - DMA_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - DMA1_FLAG_GL1: DMA1 Channel1 global flag.
+* - DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag.
+* - DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag.
+* - DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag.
+* - DMA1_FLAG_GL2: DMA1 Channel2 global flag.
+* - DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag.
+* - DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag.
+* - DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag.
+* - DMA1_FLAG_GL3: DMA1 Channel3 global flag.
+* - DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag.
+* - DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag.
+* - DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag.
+* - DMA1_FLAG_GL4: DMA1 Channel4 global flag.
+* - DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag.
+* - DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag.
+* - DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag.
+* - DMA1_FLAG_GL5: DMA1 Channel5 global flag.
+* - DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag.
+* - DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag.
+* - DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag.
+* - DMA1_FLAG_GL6: DMA1 Channel6 global flag.
+* - DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag.
+* - DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag.
+* - DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag.
+* - DMA1_FLAG_GL7: DMA1 Channel7 global flag.
+* - DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag.
+* - DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag.
+* - DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag.
+* - DMA2_FLAG_GL1: DMA2 Channel1 global flag.
+* - DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag.
+* - DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag.
+* - DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag.
+* - DMA2_FLAG_GL2: DMA2 Channel2 global flag.
+* - DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag.
+* - DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag.
+* - DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag.
+* - DMA2_FLAG_GL3: DMA2 Channel3 global flag.
+* - DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag.
+* - DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag.
+* - DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag.
+* - DMA2_FLAG_GL4: DMA2 Channel4 global flag.
+* - DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag.
+* - DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag.
+* - DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag.
+* - DMA2_FLAG_GL5: DMA2 Channel5 global flag.
+* - DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag.
+* - DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag.
+* - DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag.
+* Output : None
+* Return : The new state of DMA_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus DMA_GetFlagStatus(u32 DMA_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_DMA_GET_FLAG(DMA_FLAG));
+
+ /* Calculate the used DMA */
+ if ((DMA_FLAG & FLAG_Mask) != (u32)RESET)
+ {
+ /* Get DMA2 ISR register value */
+ tmpreg = DMA2->ISR ;
+ }
+ else
+ {
+ /* Get DMA1 ISR register value */
+ tmpreg = DMA1->ISR ;
+ }
+
+ /* Check the status of the specified DMA flag */
+ if ((tmpreg & DMA_FLAG) != (u32)RESET)
+ {
+ /* DMA_FLAG is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* DMA_FLAG is reset */
+ bitstatus = RESET;
+ }
+
+ /* Return the DMA_FLAG status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : DMA_ClearFlag
+* Description : Clears the DMAy Channelx's pending flags.
+* Input : - DMA_FLAG: specifies the flag to clear.
+* This parameter can be any combination (for the same DMA) of
+* the following values:
+* - DMA1_FLAG_GL1: DMA1 Channel1 global flag.
+* - DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag.
+* - DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag.
+* - DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag.
+* - DMA1_FLAG_GL2: DMA1 Channel2 global flag.
+* - DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag.
+* - DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag.
+* - DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag.
+* - DMA1_FLAG_GL3: DMA1 Channel3 global flag.
+* - DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag.
+* - DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag.
+* - DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag.
+* - DMA1_FLAG_GL4: DMA1 Channel4 global flag.
+* - DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag.
+* - DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag.
+* - DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag.
+* - DMA1_FLAG_GL5: DMA1 Channel5 global flag.
+* - DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag.
+* - DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag.
+* - DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag.
+* - DMA1_FLAG_GL6: DMA1 Channel6 global flag.
+* - DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag.
+* - DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag.
+* - DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag.
+* - DMA1_FLAG_GL7: DMA1 Channel7 global flag.
+* - DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag.
+* - DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag.
+* - DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag.
+* - DMA2_FLAG_GL1: DMA2 Channel1 global flag.
+* - DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag.
+* - DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag.
+* - DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag.
+* - DMA2_FLAG_GL2: DMA2 Channel2 global flag.
+* - DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag.
+* - DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag.
+* - DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag.
+* - DMA2_FLAG_GL3: DMA2 Channel3 global flag.
+* - DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag.
+* - DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag.
+* - DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag.
+* - DMA2_FLAG_GL4: DMA2 Channel4 global flag.
+* - DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag.
+* - DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag.
+* - DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag.
+* - DMA2_FLAG_GL5: DMA2 Channel5 global flag.
+* - DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag.
+* - DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag.
+* - DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_ClearFlag(u32 DMA_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_DMA_CLEAR_FLAG(DMA_FLAG));
+
+ /* Calculate the used DMA */
+ if ((DMA_FLAG & FLAG_Mask) != (u32)RESET)
+ {
+ /* Clear the selected DMA flags */
+ DMA2->IFCR = DMA_FLAG;
+ }
+ else
+ {
+ /* Clear the selected DMA flags */
+ DMA1->IFCR = DMA_FLAG;
+ }
+}
+
+/*******************************************************************************
+* Function Name : DMA_GetITStatus
+* Description : Checks whether the specified DMAy Channelx interrupt has
+* occurred or not.
+* Input : - DMA_IT: specifies the DMA interrupt source to check.
+* This parameter can be one of the following values:
+* - DMA1_IT_GL1: DMA1 Channel1 global interrupt.
+* - DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt.
+* - DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt.
+* - DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt.
+* - DMA1_IT_GL2: DMA1 Channel2 global interrupt.
+* - DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt.
+* - DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt.
+* - DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt.
+* - DMA1_IT_GL3: DMA1 Channel3 global interrupt.
+* - DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt.
+* - DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt.
+* - DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt.
+* - DMA1_IT_GL4: DMA1 Channel4 global interrupt.
+* - DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt.
+* - DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt.
+* - DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt.
+* - DMA1_IT_GL5: DMA1 Channel5 global interrupt.
+* - DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt.
+* - DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt.
+* - DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt.
+* - DMA1_IT_GL6: DMA1 Channel6 global interrupt.
+* - DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt.
+* - DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt.
+* - DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt.
+* - DMA1_IT_GL7: DMA1 Channel7 global interrupt.
+* - DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt.
+* - DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt.
+* - DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt.
+* - DMA2_IT_GL1: DMA2 Channel1 global interrupt.
+* - DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt.
+* - DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt.
+* - DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt.
+* - DMA2_IT_GL2: DMA2 Channel2 global interrupt.
+* - DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt.
+* - DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt.
+* - DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt.
+* - DMA2_IT_GL3: DMA2 Channel3 global interrupt.
+* - DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt.
+* - DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt.
+* - DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt.
+* - DMA2_IT_GL4: DMA2 Channel4 global interrupt.
+* - DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt.
+* - DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt.
+* - DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt.
+* - DMA2_IT_GL5: DMA2 Channel5 global interrupt.
+* - DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt.
+* - DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt.
+* - DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt.
+* Output : None
+* Return : The new state of DMA_IT (SET or RESET).
+*******************************************************************************/
+ITStatus DMA_GetITStatus(u32 DMA_IT)
+{
+ ITStatus bitstatus = RESET;
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_DMA_GET_IT(DMA_IT));
+
+ /* Calculate the used DMA */
+ if ((DMA_IT & FLAG_Mask) != (u32)RESET)
+ {
+ /* Get DMA2 ISR register value */
+ tmpreg = DMA2->ISR ;
+ }
+ else
+ {
+ /* Get DMA1 ISR register value */
+ tmpreg = DMA1->ISR ;
+ }
+
+ /* Check the status of the specified DMA interrupt */
+ if ((tmpreg & DMA_IT) != (u32)RESET)
+ {
+ /* DMA_IT is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* DMA_IT is reset */
+ bitstatus = RESET;
+ }
+ /* Return the DMA_IT status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : DMA_ClearITPendingBit
+* Description : Clears the DMAy Channelx’s interrupt pending bits.
+* Input : - DMA_IT: specifies the DMA interrupt pending bit to clear.
+* This parameter can be any combination (for the same DMA) of
+* the following values:
+* - DMA1_IT_GL1: DMA1 Channel1 global interrupt.
+* - DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt.
+* - DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt.
+* - DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt.
+* - DMA1_IT_GL2: DMA1 Channel2 global interrupt.
+* - DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt.
+* - DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt.
+* - DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt.
+* - DMA1_IT_GL3: DMA1 Channel3 global interrupt.
+* - DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt.
+* - DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt.
+* - DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt.
+* - DMA1_IT_GL4: DMA1 Channel4 global interrupt.
+* - DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt.
+* - DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt.
+* - DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt.
+* - DMA1_IT_GL5: DMA1 Channel5 global interrupt.
+* - DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt.
+* - DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt.
+* - DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt.
+* - DMA1_IT_GL6: DMA1 Channel6 global interrupt.
+* - DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt.
+* - DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt.
+* - DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt.
+* - DMA1_IT_GL7: DMA1 Channel7 global interrupt.
+* - DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt.
+* - DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt.
+* - DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt.
+* - DMA2_IT_GL1: DMA2 Channel1 global interrupt.
+* - DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt.
+* - DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt.
+* - DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt.
+* - DMA2_IT_GL2: DMA2 Channel2 global interrupt.
+* - DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt.
+* - DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt.
+* - DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt.
+* - DMA2_IT_GL3: DMA2 Channel3 global interrupt.
+* - DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt.
+* - DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt.
+* - DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt.
+* - DMA2_IT_GL4: DMA2 Channel4 global interrupt.
+* - DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt.
+* - DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt.
+* - DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt.
+* - DMA2_IT_GL5: DMA2 Channel5 global interrupt.
+* - DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt.
+* - DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt.
+* - DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_ClearITPendingBit(u32 DMA_IT)
+{
+ /* Check the parameters */
+ assert_param(IS_DMA_CLEAR_IT(DMA_IT));
+
+ /* Calculate the used DMA */
+ if ((DMA_IT & FLAG_Mask) != (u32)RESET)
+ {
+ /* Clear the selected DMA interrupt pending bits */
+ DMA2->IFCR = DMA_IT;
+ }
+ else
+ {
+ /* Clear the selected DMA interrupt pending bits */
+ DMA1->IFCR = DMA_IT;
+ }
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
+
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_exti.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_exti.c new file mode 100755 index 0000000..52dd587 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_exti.c @@ -0,0 +1,219 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_exti.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the EXTI firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_exti.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define EXTI_LineNone ((u32)0x00000) /* No interrupt selected */
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : EXTI_DeInit
+* Description : Deinitializes the EXTI peripheral registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_DeInit(void)
+{
+ EXTI->IMR = 0x00000000;
+ EXTI->EMR = 0x00000000;
+ EXTI->RTSR = 0x00000000;
+ EXTI->FTSR = 0x00000000;
+ EXTI->PR = 0x0007FFFF;
+}
+
+/*******************************************************************************
+* Function Name : EXTI_Init
+* Description : Initializes the EXTI peripheral according to the specified
+* parameters in the EXTI_InitStruct.
+* Input : - EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure
+* that contains the configuration information for the EXTI
+* peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_EXTI_MODE(EXTI_InitStruct->EXTI_Mode));
+ assert_param(IS_EXTI_TRIGGER(EXTI_InitStruct->EXTI_Trigger));
+ assert_param(IS_EXTI_LINE(EXTI_InitStruct->EXTI_Line));
+ assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->EXTI_LineCmd));
+
+ if (EXTI_InitStruct->EXTI_LineCmd != DISABLE)
+ {
+ /* Clear EXTI line configuration */
+ EXTI->IMR &= ~EXTI_InitStruct->EXTI_Line;
+ EXTI->EMR &= ~EXTI_InitStruct->EXTI_Line;
+
+ *(vu32 *)(EXTI_BASE + (u32)EXTI_InitStruct->EXTI_Mode)|= EXTI_InitStruct->EXTI_Line;
+
+ /* Clear Rising Falling edge configuration */
+ EXTI->RTSR &= ~EXTI_InitStruct->EXTI_Line;
+ EXTI->FTSR &= ~EXTI_InitStruct->EXTI_Line;
+
+ /* Select the trigger for the selected external interrupts */
+ if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling)
+ {
+ /* Rising Falling edge */
+ EXTI->RTSR |= EXTI_InitStruct->EXTI_Line;
+ EXTI->FTSR |= EXTI_InitStruct->EXTI_Line;
+ }
+ else
+ {
+ *(vu32 *)(EXTI_BASE + (u32)EXTI_InitStruct->EXTI_Trigger)|= EXTI_InitStruct->EXTI_Line;
+ }
+ }
+ else
+ {
+ /* Disable the selected external lines */
+ *(vu32 *)(EXTI_BASE + (u32)EXTI_InitStruct->EXTI_Mode)&= ~EXTI_InitStruct->EXTI_Line;
+ }
+}
+
+/*******************************************************************************
+* Function Name : EXTI_StructInit
+* Description : Fills each EXTI_InitStruct member with its reset value.
+* Input : - EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct)
+{
+ EXTI_InitStruct->EXTI_Line = EXTI_LineNone;
+ EXTI_InitStruct->EXTI_Mode = EXTI_Mode_Interrupt;
+ EXTI_InitStruct->EXTI_Trigger = EXTI_Trigger_Falling;
+ EXTI_InitStruct->EXTI_LineCmd = DISABLE;
+}
+
+/*******************************************************************************
+* Function Name : EXTI_GenerateSWInterrupt
+* Description : Generates a Software interrupt.
+* Input : - EXTI_Line: specifies the EXTI lines to be enabled or
+* disabled.
+* This parameter can be any combination of EXTI_Linex where
+* x can be (0..18).
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_GenerateSWInterrupt(u32 EXTI_Line)
+{
+ /* Check the parameters */
+ assert_param(IS_EXTI_LINE(EXTI_Line));
+
+ EXTI->SWIER |= EXTI_Line;
+}
+
+/*******************************************************************************
+* Function Name : EXTI_GetFlagStatus
+* Description : Checks whether the specified EXTI line flag is set or not.
+* Input : - EXTI_Line: specifies the EXTI line flag to check.
+* This parameter can be:
+* - EXTI_Linex: External interrupt line x where x(0..18)
+* Output : None
+* Return : The new state of EXTI_Line (SET or RESET).
+*******************************************************************************/
+FlagStatus EXTI_GetFlagStatus(u32 EXTI_Line)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_GET_EXTI_LINE(EXTI_Line));
+
+ if ((EXTI->PR & EXTI_Line) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : EXTI_ClearFlag
+* Description : Clears the EXTI’s line pending flags.
+* Input : - EXTI_Line: specifies the EXTI lines flags to clear.
+* This parameter can be any combination of EXTI_Linex where
+* x can be (0..18).
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_ClearFlag(u32 EXTI_Line)
+{
+ /* Check the parameters */
+ assert_param(IS_EXTI_LINE(EXTI_Line));
+
+ EXTI->PR = EXTI_Line;
+}
+
+/*******************************************************************************
+* Function Name : EXTI_GetITStatus
+* Description : Checks whether the specified EXTI line is asserted or not.
+* Input : - EXTI_Line: specifies the EXTI line to check.
+* This parameter can be:
+* - EXTI_Linex: External interrupt line x where x(0..18)
+* Output : None
+* Return : The new state of EXTI_Line (SET or RESET).
+*******************************************************************************/
+ITStatus EXTI_GetITStatus(u32 EXTI_Line)
+{
+ ITStatus bitstatus = RESET;
+ u32 enablestatus = 0;
+
+ /* Check the parameters */
+ assert_param(IS_GET_EXTI_LINE(EXTI_Line));
+
+ enablestatus = EXTI->IMR & EXTI_Line;
+
+ if (((EXTI->PR & EXTI_Line) != (u32)RESET) && (enablestatus != (u32)RESET))
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : EXTI_ClearITPendingBit
+* Description : Clears the EXTI’s line pending bits.
+* Input : - EXTI_Line: specifies the EXTI lines to clear.
+* This parameter can be any combination of EXTI_Linex where
+* x can be (0..18).
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_ClearITPendingBit(u32 EXTI_Line)
+{
+ /* Check the parameters */
+ assert_param(IS_EXTI_LINE(EXTI_Line));
+
+ EXTI->PR = EXTI_Line;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_flash.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_flash.c new file mode 100755 index 0000000..795e008 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_flash.c @@ -0,0 +1,920 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_flash.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the FLASH firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_flash.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Flash Access Control Register bits */
+#define ACR_LATENCY_Mask ((u32)0x00000038)
+#define ACR_HLFCYA_Mask ((u32)0xFFFFFFF7)
+#define ACR_PRFTBE_Mask ((u32)0xFFFFFFEF)
+
+#ifdef _FLASH_PROG
+/* Flash Access Control Register bits */
+#define ACR_PRFTBS_Mask ((u32)0x00000020)
+
+/* Flash Control Register bits */
+#define CR_PG_Set ((u32)0x00000001)
+#define CR_PG_Reset ((u32)0x00001FFE)
+
+#define CR_PER_Set ((u32)0x00000002)
+#define CR_PER_Reset ((u32)0x00001FFD)
+
+#define CR_MER_Set ((u32)0x00000004)
+#define CR_MER_Reset ((u32)0x00001FFB)
+
+#define CR_OPTPG_Set ((u32)0x00000010)
+#define CR_OPTPG_Reset ((u32)0x00001FEF)
+
+#define CR_OPTER_Set ((u32)0x00000020)
+#define CR_OPTER_Reset ((u32)0x00001FDF)
+
+#define CR_STRT_Set ((u32)0x00000040)
+
+#define CR_LOCK_Set ((u32)0x00000080)
+
+/* FLASH Mask */
+#define RDPRT_Mask ((u32)0x00000002)
+#define WRP0_Mask ((u32)0x000000FF)
+#define WRP1_Mask ((u32)0x0000FF00)
+#define WRP2_Mask ((u32)0x00FF0000)
+#define WRP3_Mask ((u32)0xFF000000)
+
+/* FLASH Keys */
+#define RDP_Key ((u16)0x00A5)
+#define FLASH_KEY1 ((u32)0x45670123)
+#define FLASH_KEY2 ((u32)0xCDEF89AB)
+
+/* Delay definition */
+#define EraseTimeout ((u32)0x00000FFF)
+#define ProgramTimeout ((u32)0x0000000F)
+#endif
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+#ifdef _FLASH_PROG
+static void delay(void);
+#endif
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : FLASH_SetLatency
+* Description : Sets the code latency value.
+* Input : - FLASH_Latency: specifies the FLASH Latency value.
+* This parameter can be one of the following values:
+* - FLASH_Latency_0: FLASH Zero Latency cycle
+* - FLASH_Latency_1: FLASH One Latency cycle
+* - FLASH_Latency_2: FLASH Two Latency cycles
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_SetLatency(u32 FLASH_Latency)
+{
+ /* Check the parameters */
+ assert_param(IS_FLASH_LATENCY(FLASH_Latency));
+
+ /* Sets the Latency value */
+ FLASH->ACR &= ACR_LATENCY_Mask;
+ FLASH->ACR |= FLASH_Latency;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_HalfCycleAccessCmd
+* Description : Enables or disables the Half cycle flash access.
+* Input : - FLASH_HalfCycle: specifies the FLASH Half cycle Access mode.
+* This parameter can be one of the following values:
+* - FLASH_HalfCycleAccess_Enable: FLASH Half Cycle Enable
+* - FLASH_HalfCycleAccess_Disable: FLASH Half Cycle Disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_HalfCycleAccessCmd(u32 FLASH_HalfCycleAccess)
+{
+ /* Check the parameters */
+ assert_param(IS_FLASH_HALFCYCLEACCESS_STATE(FLASH_HalfCycleAccess));
+
+ /* Enable or disable the Half cycle access */
+ FLASH->ACR &= ACR_HLFCYA_Mask;
+ FLASH->ACR |= FLASH_HalfCycleAccess;
+}
+
+void test(u32 x) {
+ int x;
+ int y;
+ x = 1;
+ y = x;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_PrefetchBufferCmd
+* Description : Enables or disables the Prefetch Buffer.
+* Input : - FLASH_PrefetchBuffer: specifies the Prefetch buffer status.
+* This parameter can be one of the following values:
+* - FLASH_PrefetchBuffer_Enable: FLASH Prefetch Buffer Enable
+* - FLASH_PrefetchBuffer_Disable: FLASH Prefetch Buffer Disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_PrefetchBufferCmd(u32 FLASH_PrefetchBuffer)
+{
+ /* Check the parameters */
+ assert_param(IS_FLASH_PREFETCHBUFFER_STATE(FLASH_PrefetchBuffer));
+ assert_param(IS_FLASH_PREFETCHBUFFER_STATE(FLASH_PrefetchBuffer));
+ assert_param(IS_FLASH_PREFETCHBUFFER_STATE(FLASH_PrefetchBuffer));
+
+ /* Enable or disable the Prefetch Buffer */
+ FLASH->ACR &= ACR_PRFTBE_Mask;
+ FLASH->ACR |= FLASH_PrefetchBuffer;
+}
+
+#ifdef _FLASH_PROG
+/*******************************************************************************
+* Function Name : FLASH_Unlock
+* Description : Unlocks the FLASH Program Erase Controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_Unlock(void)
+{
+ /* Authorize the FPEC Access */
+ FLASH->KEYR = FLASH_KEY1;
+ FLASH->KEYR = FLASH_KEY2;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_Lock
+* Description : Locks the FLASH Program Erase Controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_Lock(void)
+{
+ /* Set the Lock Bit to lock the FPEC and the FCR */
+ FLASH->CR |= CR_LOCK_Set;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_ErasePage
+* Description : Erases a specified FLASH page.
+* Input : - Page_Address: The page address to be erased.
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_ErasePage(u32 Page_Address)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_ADDRESS(Page_Address));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the previous operation is completed, proceed to erase the page */
+ FLASH->CR|= CR_PER_Set;
+ FLASH->AR = Page_Address;
+ FLASH->CR|= CR_STRT_Set;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the erase operation is completed, disable the PER Bit */
+ FLASH->CR &= CR_PER_Reset;
+ }
+ }
+ /* Return the Erase Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_EraseAllPages
+* Description : Erases all FLASH pages.
+* Input : None
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_EraseAllPages(void)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the previous operation is completed, proceed to erase all pages */
+ FLASH->CR |= CR_MER_Set;
+ FLASH->CR |= CR_STRT_Set;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the erase operation is completed, disable the MER Bit */
+ FLASH->CR &= CR_MER_Reset;
+ }
+ }
+ /* Return the Erase Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_EraseOptionBytes
+* Description : Erases the FLASH option bytes.
+* Input : None
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_EraseOptionBytes(void)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* Authorize the small information block programming */
+ FLASH->OPTKEYR = FLASH_KEY1;
+ FLASH->OPTKEYR = FLASH_KEY2;
+
+ /* if the previous operation is completed, proceed to erase the option bytes */
+ FLASH->CR |= CR_OPTER_Set;
+ FLASH->CR |= CR_STRT_Set;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the erase operation is completed, disable the OPTER Bit */
+ FLASH->CR &= CR_OPTER_Reset;
+
+ /* Enable the Option Bytes Programming operation */
+ FLASH->CR |= CR_OPTPG_Set;
+
+ /* Enable the readout access */
+ OB->RDP= RDP_Key;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the program operation is completed, disable the OPTPG Bit */
+ FLASH->CR &= CR_OPTPG_Reset;
+ }
+ }
+ else
+ {
+ if (status != FLASH_BUSY)
+ {
+ /* Disable the OPTPG Bit */
+ FLASH->CR &= CR_OPTPG_Reset;
+ }
+ }
+ }
+ /* Return the erase status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_ProgramWord
+* Description : Programs a word at a specified address.
+* Input : - Address: specifies the address to be programmed.
+* - Data: specifies the data to be programmed.
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_ProgramWord(u32 Address, u32 Data)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_ADDRESS(Address));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the previous operation is completed, proceed to program the new first
+ half word */
+ FLASH->CR |= CR_PG_Set;
+
+ *(vu16*)Address = (u16)Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the previous operation is completed, proceed to program the new second
+ half word */
+ *(vu16*)(Address + 2) = Data >> 16;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* Disable the PG Bit */
+ FLASH->CR &= CR_PG_Reset;
+ }
+ }
+ else
+ {
+ if (status != FLASH_BUSY)
+ {
+ /* Disable the PG Bit */
+ FLASH->CR &= CR_PG_Reset;
+ }
+ }
+ }
+ /* Return the Program Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_ProgramHalfWord
+* Description : Programs a half word at a specified address.
+* Input : - Address: specifies the address to be programmed.
+* - Data: specifies the data to be programmed.
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_ProgramHalfWord(u32 Address, u16 Data)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_ADDRESS(Address));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the previous operation is completed, proceed to program the new data */
+ FLASH->CR |= CR_PG_Set;
+
+ *(vu16*)Address = Data;
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the program operation is completed, disable the PG Bit */
+ FLASH->CR &= CR_PG_Reset;
+ }
+ }
+ /* Return the Program Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_ProgramOptionByteData
+* Description : Programs a half word at a specified Option Byte Data address.
+* Input : - Address: specifies the address to be programmed.
+* This parameter can be 0x1FFFF804 or 0x1FFFF806.
+* - Data: specifies the data to be programmed.
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_ProgramOptionByteData(u32 Address, u8 Data)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check the parameters */
+ assert_param(IS_OB_DATA_ADDRESS(Address));
+
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* Authorize the small information block programming */
+ FLASH->OPTKEYR = FLASH_KEY1;
+ FLASH->OPTKEYR = FLASH_KEY2;
+
+ /* Enables the Option Bytes Programming operation */
+ FLASH->CR |= CR_OPTPG_Set;
+ *(vu16*)Address = Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the program operation is completed, disable the OPTPG Bit */
+ FLASH->CR &= CR_OPTPG_Reset;
+ }
+ }
+ /* Return the Option Byte Data Program Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_EnableWriteProtection
+* Description : Write protects the desired pages
+* Input : - FLASH_Pages: specifies the address of the pages to be
+* write protected. This parameter can be:
+* - For STM32F10Xxx Medium-density devices (FLASH page size equal to 1 KB)
+* - A value between FLASH_WRProt_Pages0to3 and
+* FLASH_WRProt_Pages124to127
+* - For STM32F10Xxx High-density devices (FLASH page size equal to 2 KB)
+* - A value between FLASH_WRProt_Pages0to1 and
+* FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to255
+* - FLASH_WRProt_AllPages
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_EnableWriteProtection(u32 FLASH_Pages)
+{
+ u16 WRP0_Data = 0xFFFF, WRP1_Data = 0xFFFF, WRP2_Data = 0xFFFF, WRP3_Data = 0xFFFF;
+
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_WRPROT_PAGE(FLASH_Pages));
+
+ FLASH_Pages = (u32)(~FLASH_Pages);
+ WRP0_Data = (vu16)(FLASH_Pages & WRP0_Mask);
+ WRP1_Data = (vu16)((FLASH_Pages & WRP1_Mask) >> 8);
+ WRP2_Data = (vu16)((FLASH_Pages & WRP2_Mask) >> 16);
+ WRP3_Data = (vu16)((FLASH_Pages & WRP3_Mask) >> 24);
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* Authorizes the small information block programming */
+ FLASH->OPTKEYR = FLASH_KEY1;
+ FLASH->OPTKEYR = FLASH_KEY2;
+ FLASH->CR |= CR_OPTPG_Set;
+
+ if(WRP0_Data != 0xFF)
+ {
+ OB->WRP0 = WRP0_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+ }
+ if((status == FLASH_COMPLETE) && (WRP1_Data != 0xFF))
+ {
+ OB->WRP1 = WRP1_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+ }
+
+ if((status == FLASH_COMPLETE) && (WRP2_Data != 0xFF))
+ {
+ OB->WRP2 = WRP2_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+ }
+
+ if((status == FLASH_COMPLETE)&& (WRP3_Data != 0xFF))
+ {
+ OB->WRP3 = WRP3_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+ }
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the program operation is completed, disable the OPTPG Bit */
+ FLASH->CR &= CR_OPTPG_Reset;
+ }
+ }
+ /* Return the write protection operation Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_ReadOutProtection
+* Description : Enables or disables the read out protection.
+* If the user has already programmed the other option bytes before
+* calling this function, he must re-program them since this
+* function erases all option bytes.
+* Input : - Newstate: new state of the ReadOut Protection.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* Authorizes the small information block programming */
+ FLASH->OPTKEYR = FLASH_KEY1;
+ FLASH->OPTKEYR = FLASH_KEY2;
+
+ FLASH->CR |= CR_OPTER_Set;
+ FLASH->CR |= CR_STRT_Set;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the erase operation is completed, disable the OPTER Bit */
+ FLASH->CR &= CR_OPTER_Reset;
+
+ /* Enable the Option Bytes Programming operation */
+ FLASH->CR |= CR_OPTPG_Set;
+
+ if(NewState != DISABLE)
+ {
+ OB->RDP = 0x00;
+ }
+ else
+ {
+ OB->RDP = RDP_Key;
+ }
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the program operation is completed, disable the OPTPG Bit */
+ FLASH->CR &= CR_OPTPG_Reset;
+ }
+ }
+ else
+ {
+ if(status != FLASH_BUSY)
+ {
+ /* Disable the OPTER Bit */
+ FLASH->CR &= CR_OPTER_Reset;
+ }
+ }
+ }
+ /* Return the protection operation Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_UserOptionByteConfig
+* Description : Programs the FLASH User Option Byte: IWDG_SW / RST_STOP /
+* RST_STDBY.
+* Input : - OB_IWDG: Selects the IWDG mode
+* This parameter can be one of the following values:
+* - OB_IWDG_SW: Software IWDG selected
+* - OB_IWDG_HW: Hardware IWDG selected
+* - OB_STOP: Reset event when entering STOP mode.
+* This parameter can be one of the following values:
+* - OB_STOP_NoRST: No reset generated when entering in STOP
+* - OB_STOP_RST: Reset generated when entering in STOP
+* - OB_STDBY: Reset event when entering Standby mode.
+* This parameter can be one of the following values:
+* - OB_STDBY_NoRST: No reset generated when entering in STANDBY
+* - OB_STDBY_RST: Reset generated when entering in STANDBY
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_UserOptionByteConfig(u16 OB_IWDG, u16 OB_STOP, u16 OB_STDBY)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check the parameters */
+ assert_param(IS_OB_IWDG_SOURCE(OB_IWDG));
+ assert_param(IS_OB_STOP_SOURCE(OB_STOP));
+ assert_param(IS_OB_STDBY_SOURCE(OB_STDBY));
+
+ /* Authorize the small information block programming */
+ FLASH->OPTKEYR = FLASH_KEY1;
+ FLASH->OPTKEYR = FLASH_KEY2;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* Enable the Option Bytes Programming operation */
+ FLASH->CR |= CR_OPTPG_Set;
+
+ OB->USER = ( OB_IWDG | OB_STOP |OB_STDBY) | (u16)0xF8;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the program operation is completed, disable the OPTPG Bit */
+ FLASH->CR &= CR_OPTPG_Reset;
+ }
+ }
+ /* Return the Option Byte program Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_GetUserOptionByte
+* Description : Returns the FLASH User Option Bytes values.
+* Input : None
+* Output : None
+* Return : The FLASH User Option Bytes values:IWDG_SW(Bit0), RST_STOP(Bit1)
+* and RST_STDBY(Bit2).
+*******************************************************************************/
+u32 FLASH_GetUserOptionByte(void)
+{
+ /* Return the User Option Byte */
+ return (u32)(FLASH->OBR >> 2);
+}
+
+/*******************************************************************************
+* Function Name : FLASH_GetWriteProtectionOptionByte
+* Description : Returns the FLASH Write Protection Option Bytes Register value.
+* Input : None
+* Output : None
+* Return : The FLASH Write Protection Option Bytes Register value
+*******************************************************************************/
+u32 FLASH_GetWriteProtectionOptionByte(void)
+{
+ /* Return the Falsh write protection Register value */
+ return (u32)(FLASH->WRPR);
+}
+
+/*******************************************************************************
+* Function Name : FLASH_GetReadOutProtectionStatus
+* Description : Checks whether the FLASH Read Out Protection Status is set
+* or not.
+* Input : None
+* Output : None
+* Return : FLASH ReadOut Protection Status(SET or RESET)
+*******************************************************************************/
+FlagStatus FLASH_GetReadOutProtectionStatus(void)
+{
+ FlagStatus readoutstatus = RESET;
+
+ if ((FLASH->OBR & RDPRT_Mask) != (u32)RESET)
+ {
+ readoutstatus = SET;
+ }
+ else
+ {
+ readoutstatus = RESET;
+ }
+ return readoutstatus;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_GetPrefetchBufferStatus
+* Description : Checks whether the FLASH Prefetch Buffer status is set or not.
+* Input : None
+* Output : None
+* Return : FLASH Prefetch Buffer Status (SET or RESET).
+*******************************************************************************/
+FlagStatus FLASH_GetPrefetchBufferStatus(void)
+{
+ FlagStatus bitstatus = RESET;
+
+ if ((FLASH->ACR & ACR_PRFTBS_Mask) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ /* Return the new state of FLASH Prefetch Buffer Status (SET or RESET) */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_ITConfig
+* Description : Enables or disables the specified FLASH interrupts.
+* Input : - FLASH_IT: specifies the FLASH interrupt sources to be
+* enabled or disabled.
+* This parameter can be any combination of the following values:
+* - FLASH_IT_ERROR: FLASH Error Interrupt
+* - FLASH_IT_EOP: FLASH end of operation Interrupt
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_ITConfig(u16 FLASH_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FLASH_IT(FLASH_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if(NewState != DISABLE)
+ {
+ /* Enable the interrupt sources */
+ FLASH->CR |= FLASH_IT;
+ }
+ else
+ {
+ /* Disable the interrupt sources */
+ FLASH->CR &= ~(u32)FLASH_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FLASH_GetFlagStatus
+* Description : Checks whether the specified FLASH flag is set or not.
+* Input : - FLASH_FLAG: specifies the FLASH flag to check.
+* This parameter can be one of the following values:
+* - FLASH_FLAG_BSY: FLASH Busy flag
+* - FLASH_FLAG_PGERR: FLASH Program error flag
+* - FLASH_FLAG_WRPRTERR: FLASH Write protected error flag
+* - FLASH_FLAG_EOP: FLASH End of Operation flag
+* - FLASH_FLAG_OPTERR: FLASH Option Byte error flag
+* Output : None
+* Return : The new state of FLASH_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus FLASH_GetFlagStatus(u16 FLASH_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG)) ;
+
+ if(FLASH_FLAG == FLASH_FLAG_OPTERR)
+ {
+ if((FLASH->OBR & FLASH_FLAG_OPTERR) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ }
+ else
+ {
+ if((FLASH->SR & FLASH_FLAG) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ }
+ /* Return the new state of FLASH_FLAG (SET or RESET) */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_ClearFlag
+* Description : Clears the FLASH’s pending flags.
+* Input : - FLASH_FLAG: specifies the FLASH flags to clear.
+* This parameter can be any combination of the following values:
+* - FLASH_FLAG_BSY: FLASH Busy flag
+* - FLASH_FLAG_PGERR: FLASH Program error flag
+* - FLASH_FLAG_WRPRTERR: FLASH Write protected error flag
+* - FLASH_FLAG_EOP: FLASH End of Operation flag
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_ClearFlag(u16 FLASH_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG)) ;
+
+ /* Clear the flags */
+ FLASH->SR = FLASH_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_GetStatus
+* Description : Returns the FLASH Status.
+* Input : None
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP or FLASH_COMPLETE
+*******************************************************************************/
+FLASH_Status FLASH_GetStatus(void)
+{
+ FLASH_Status flashstatus = FLASH_COMPLETE;
+
+ if((FLASH->SR & FLASH_FLAG_BSY) == FLASH_FLAG_BSY)
+ {
+ flashstatus = FLASH_BUSY;
+ }
+ else
+ {
+ if(FLASH->SR & FLASH_FLAG_PGERR)
+ {
+ flashstatus = FLASH_ERROR_PG;
+ }
+ else
+ {
+ if(FLASH->SR & FLASH_FLAG_WRPRTERR)
+ {
+ flashstatus = FLASH_ERROR_WRP;
+ }
+ else
+ {
+ flashstatus = FLASH_COMPLETE;
+ }
+ }
+ }
+ /* Return the Flash Status */
+ return flashstatus;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_WaitForLastOperation
+* Description : Waits for a Flash operation to complete or a TIMEOUT to occur.
+* Input : - Timeout: FLASH progamming Timeout
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_WaitForLastOperation(u32 Timeout)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check for the Flash Status */
+ status = FLASH_GetStatus();
+
+ /* Wait for a Flash operation to complete or a TIMEOUT to occur */
+ while((status == FLASH_BUSY) && (Timeout != 0x00))
+ {
+ delay();
+ status = FLASH_GetStatus();
+ Timeout--;
+ }
+
+ if(Timeout == 0x00 )
+ {
+ status = FLASH_TIMEOUT;
+ }
+
+ /* Return the operation status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : delay
+* Description : Inserts a time delay.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+static void delay(void)
+{
+ vu32 i = 0;
+
+ for(i = 0xFF; i != 0; i--)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_fsmc.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_fsmc.c new file mode 100755 index 0000000..b0114bf --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_fsmc.c @@ -0,0 +1,861 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_fsmc.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the FSMC firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_fsmc.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* --------------------- FSMC registers bit mask ---------------------------- */
+/* FSMC BCRx Mask */
+#define BCR_MBKEN_Set ((u32)0x00000001)
+#define BCR_MBKEN_Reset ((u32)0x000FFFFE)
+#define BCR_FACCEN_Set ((u32)0x00000040)
+
+/* FSMC PCRx Mask */
+#define PCR_PBKEN_Set ((u32)0x00000004)
+#define PCR_PBKEN_Reset ((u32)0x000FFFFB)
+#define PCR_ECCEN_Set ((u32)0x00000040)
+#define PCR_ECCEN_Reset ((u32)0x000FFFBF)
+#define PCR_MemoryType_NAND ((u32)0x00000008)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : FSMC_NORSRAMDeInit
+* Description : Deinitializes the FSMC NOR/SRAM Banks registers to their default
+* reset values.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1
+* - FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2
+* - FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3
+* - FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NORSRAMDeInit(u32 FSMC_Bank)
+{
+ /* Check the parameter */
+ assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank));
+
+ /* FSMC_Bank1_NORSRAM1 */
+ if(FSMC_Bank == FSMC_Bank1_NORSRAM1)
+ {
+ FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030DB;
+ }
+ /* FSMC_Bank1_NORSRAM2, FSMC_Bank1_NORSRAM3 or FSMC_Bank1_NORSRAM4 */
+ else
+ {
+ FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030D2;
+ }
+
+ FSMC_Bank1->BTCR[FSMC_Bank + 1] = 0x0FFFFFFF;
+ FSMC_Bank1E->BWTR[FSMC_Bank] = 0x0FFFFFFF;
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NANDDeInit
+* Description : Deinitializes the FSMC NAND Banks registers to their default
+* reset values.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NANDDeInit(u32 FSMC_Bank)
+{
+ /* Check the parameter */
+ assert_param(IS_FSMC_NAND_BANK(FSMC_Bank));
+
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ /* Set the FSMC_Bank2 registers to their reset values */
+ FSMC_Bank2->PCR2 = 0x00000018;
+ FSMC_Bank2->SR2 = 0x00000040;
+ FSMC_Bank2->PMEM2 = 0xFCFCFCFC;
+ FSMC_Bank2->PATT2 = 0xFCFCFCFC;
+ }
+ /* FSMC_Bank3_NAND */
+ else
+ {
+ /* Set the FSMC_Bank3 registers to their reset values */
+ FSMC_Bank3->PCR3 = 0x00000018;
+ FSMC_Bank3->SR3 = 0x00000040;
+ FSMC_Bank3->PMEM3 = 0xFCFCFCFC;
+ FSMC_Bank3->PATT3 = 0xFCFCFCFC;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_PCCARDDeInit
+* Description : Deinitializes the FSMC PCCARD Bank registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_PCCARDDeInit(void)
+{
+ /* Set the FSMC_Bank4 registers to their reset values */
+ FSMC_Bank4->PCR4 = 0x00000018;
+ FSMC_Bank4->SR4 = 0x00000000;
+ FSMC_Bank4->PMEM4 = 0xFCFCFCFC;
+ FSMC_Bank4->PATT4 = 0xFCFCFCFC;
+ FSMC_Bank4->PIO4 = 0xFCFCFCFC;
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NORSRAMInit
+* Description : Initializes the FSMC NOR/SRAM Banks according to the
+* specified parameters in the FSMC_NORSRAMInitStruct.
+* Input : - FSMC_NORSRAMInitStruct : pointer to a FSMC_NORSRAMInitTypeDef
+* structure that contains the configuration information for
+* the FSMC NOR/SRAM specified Banks.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_FSMC_NORSRAM_BANK(FSMC_NORSRAMInitStruct->FSMC_Bank));
+ assert_param(IS_FSMC_MUX(FSMC_NORSRAMInitStruct->FSMC_DataAddressMux));
+ assert_param(IS_FSMC_MEMORY(FSMC_NORSRAMInitStruct->FSMC_MemoryType));
+ assert_param(IS_FSMC_MEMORY_WIDTH(FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth));
+ assert_param(IS_FSMC_BURSTMODE(FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode));
+ assert_param(IS_FSMC_WAIT_POLARITY(FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity));
+ assert_param(IS_FSMC_WRAP_MODE(FSMC_NORSRAMInitStruct->FSMC_WrapMode));
+ assert_param(IS_FSMC_WAIT_SIGNAL_ACTIVE(FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive));
+ assert_param(IS_FSMC_WRITE_OPERATION(FSMC_NORSRAMInitStruct->FSMC_WriteOperation));
+ assert_param(IS_FSMC_WAITE_SIGNAL(FSMC_NORSRAMInitStruct->FSMC_WaitSignal));
+ assert_param(IS_FSMC_EXTENDED_MODE(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode));
+ assert_param(IS_FSMC_ASYNC_WAIT(FSMC_NORSRAMInitStruct->FSMC_AsyncWait));
+ assert_param(IS_FSMC_WRITE_BURST(FSMC_NORSRAMInitStruct->FSMC_WriteBurst));
+ assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime));
+ assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime));
+ assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime));
+ assert_param(IS_FSMC_TURNAROUND_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration));
+ assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision));
+ assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency));
+ assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode));
+
+ /* Bank1 NOR/SRAM control register configuration */
+ FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] =
+ (u32)FSMC_NORSRAMInitStruct->FSMC_DataAddressMux |
+ FSMC_NORSRAMInitStruct->FSMC_MemoryType |
+ FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth |
+ FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode |
+ FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity |
+ FSMC_NORSRAMInitStruct->FSMC_WrapMode |
+ FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive |
+ FSMC_NORSRAMInitStruct->FSMC_WriteOperation |
+ FSMC_NORSRAMInitStruct->FSMC_WaitSignal |
+ FSMC_NORSRAMInitStruct->FSMC_ExtendedMode |
+ FSMC_NORSRAMInitStruct->FSMC_AsyncWait |
+ FSMC_NORSRAMInitStruct->FSMC_WriteBurst;
+
+ if(FSMC_NORSRAMInitStruct->FSMC_MemoryType == FSMC_MemoryType_NOR)
+ {
+ FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] |= (u32)BCR_FACCEN_Set;
+ }
+
+ /* Bank1 NOR/SRAM timing register configuration */
+ FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank+1] =
+ (u32)FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime |
+ (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime << 4) |
+ (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime << 8) |
+ (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration << 16) |
+ (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision << 20) |
+ (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency << 24) |
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode;
+
+
+
+ /* Bank1 NOR/SRAM timing register for write configuration, if extended mode is used */
+ if(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode == FSMC_ExtendedMode_Enable)
+ {
+ assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime));
+ assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime));
+ assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime));
+ assert_param(IS_FSMC_TURNAROUND_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_BusTurnAroundDuration));
+ assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision));
+ assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency));
+ assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode));
+
+ FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] =
+ (u32)FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime |
+ (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime << 4 )|
+ (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime << 8) |
+ (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_BusTurnAroundDuration << 16) |
+ (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision << 20) |
+ (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency << 24) |
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode;
+ }
+ else
+ {
+ FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = 0x0FFFFFFF;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NANDInit
+* Description : Initializes the FSMC NAND Banks according to the specified
+* parameters in the FSMC_NANDInitStruct.
+* Input : - FSMC_NANDInitStruct : pointer to a FSMC_NANDInitTypeDef
+* structure that contains the configuration information for
+* the FSMC NAND specified Banks.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct)
+{
+ u32 tmppcr = 0x00000000, tmppmem = 0x00000000, tmppatt = 0x00000000;
+
+ /* Check the parameters */
+ assert_param( IS_FSMC_NAND_BANK(FSMC_NANDInitStruct->FSMC_Bank));
+ assert_param( IS_FSMC_WAIT_FEATURE(FSMC_NANDInitStruct->FSMC_Waitfeature));
+ assert_param( IS_FSMC_DATA_WIDTH(FSMC_NANDInitStruct->FSMC_MemoryDataWidth));
+ assert_param( IS_FSMC_ECC_STATE(FSMC_NANDInitStruct->FSMC_ECC));
+ assert_param( IS_FSMC_ECCPAGE_SIZE(FSMC_NANDInitStruct->FSMC_ECCPageSize));
+ assert_param( IS_FSMC_ADDRESS_LOW_MAPPING(FSMC_NANDInitStruct->FSMC_AddressLowMapping));
+ assert_param( IS_FSMC_TCLR_TIME(FSMC_NANDInitStruct->FSMC_TCLRSetupTime));
+ assert_param( IS_FSMC_TAR_TIME(FSMC_NANDInitStruct->FSMC_TARSetupTime));
+
+ assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime));
+ assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime));
+ assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime));
+ assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime));
+
+ assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime));
+ assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime));
+ assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime));
+ assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime));
+
+ /* Set the tmppcr value according to FSMC_NANDInitStruct parameters */
+ tmppcr = (u32)FSMC_NANDInitStruct->FSMC_Waitfeature |
+ PCR_MemoryType_NAND |
+ FSMC_NANDInitStruct->FSMC_MemoryDataWidth |
+ FSMC_NANDInitStruct->FSMC_ECC |
+ FSMC_NANDInitStruct->FSMC_ECCPageSize |
+ FSMC_NANDInitStruct->FSMC_AddressLowMapping |
+ (FSMC_NANDInitStruct->FSMC_TCLRSetupTime << 9 )|
+ (FSMC_NANDInitStruct->FSMC_TARSetupTime << 13);
+
+ /* Set tmppmem value according to FSMC_CommonSpaceTimingStructure parameters */
+ tmppmem = (u32)FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime |
+ (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+ (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+ (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24);
+
+ /* Set tmppatt value according to FSMC_AttributeSpaceTimingStructure parameters */
+ tmppatt = (u32)FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime |
+ (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+ (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+ (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24);
+
+ if(FSMC_NANDInitStruct->FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ /* FSMC_Bank2_NAND registers configuration */
+ FSMC_Bank2->PCR2 = tmppcr;
+ FSMC_Bank2->PMEM2 = tmppmem;
+ FSMC_Bank2->PATT2 = tmppatt;
+ }
+ else
+ {
+ /* FSMC_Bank3_NAND registers configuration */
+ FSMC_Bank3->PCR3 = tmppcr;
+ FSMC_Bank3->PMEM3 = tmppmem;
+ FSMC_Bank3->PATT3 = tmppatt;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_PCCARDInit
+* Description : Initializes the FSMC PCCARD Bank according to the specified
+* parameters in the FSMC_PCCARDInitStruct.
+* Input : - FSMC_PCCARDInitStruct : pointer to a FSMC_PCCARDInitTypeDef
+* structure that contains the configuration information for
+* the FSMC PCCARD Bank.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_FSMC_WAIT_FEATURE(FSMC_PCCARDInitStruct->FSMC_Waitfeature));
+ assert_param(IS_FSMC_ADDRESS_LOW_MAPPING(FSMC_PCCARDInitStruct->FSMC_AddressLowMapping));
+ assert_param(IS_FSMC_TCLR_TIME(FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime));
+ assert_param(IS_FSMC_TAR_TIME(FSMC_PCCARDInitStruct->FSMC_TARSetupTime));
+
+
+ assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime));
+ assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime));
+ assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime));
+ assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime));
+
+ assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime));
+ assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime));
+ assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime));
+ assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime));
+
+ assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime));
+ assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime));
+ assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime));
+ assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime));
+
+ /* Set the PCR4 register value according to FSMC_PCCARDInitStruct parameters */
+ FSMC_Bank4->PCR4 = (u32)FSMC_PCCARDInitStruct->FSMC_Waitfeature |
+ FSMC_PCCARDInitStruct->FSMC_AddressLowMapping |
+ (FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime << 9) |
+ (FSMC_PCCARDInitStruct->FSMC_TARSetupTime << 13);
+
+ /* Set PMEM4 register value according to FSMC_CommonSpaceTimingStructure parameters */
+ FSMC_Bank4->PMEM4 = (u32)FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime |
+ (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+ (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+ (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24);
+
+ /* Set PATT4 register value according to FSMC_AttributeSpaceTimingStructure parameters */
+ FSMC_Bank4->PATT4 = (u32)FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime |
+ (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+ (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+ (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24);
+
+ /* Set PIO4 register value according to FSMC_IOSpaceTimingStructure parameters */
+ FSMC_Bank4->PIO4 = (u32)FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime |
+ (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+ (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+ (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime << 24);
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NORSRAMStructInit
+* Description : Fills each FSMC_NORSRAMInitStruct member with its default value.
+* Input : - FSMC_NORSRAMInitStruct: pointer to a FSMC_NORSRAMInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct)
+{
+ /* Reset NOR/SRAM Init structure parameters values */
+ FSMC_NORSRAMInitStruct->FSMC_Bank = FSMC_Bank1_NORSRAM1;
+ FSMC_NORSRAMInitStruct->FSMC_DataAddressMux = FSMC_DataAddressMux_Enable;
+ FSMC_NORSRAMInitStruct->FSMC_MemoryType = FSMC_MemoryType_SRAM;
+ FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b;
+ FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+ FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+ FSMC_NORSRAMInitStruct->FSMC_WrapMode = FSMC_WrapMode_Disable;
+ FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+ FSMC_NORSRAMInitStruct->FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+ FSMC_NORSRAMInitStruct->FSMC_WaitSignal = FSMC_WaitSignal_Enable;
+ FSMC_NORSRAMInitStruct->FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+ FSMC_NORSRAMInitStruct->FSMC_AsyncWait = FSMC_AsyncWait_Disable;
+ FSMC_NORSRAMInitStruct->FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime = 0xFF;
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A;
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime = 0xFF;
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A;
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NANDStructInit
+* Description : Fills each FSMC_NANDInitStruct member with its default value.
+* Input : - FSMC_NORSRAMInitStruct: pointer to a FSMC_NANDInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct)
+{
+ /* Reset NAND Init structure parameters values */
+ FSMC_NANDInitStruct->FSMC_Bank = FSMC_Bank2_NAND;
+ FSMC_NANDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable;
+ FSMC_NANDInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b;
+ FSMC_NANDInitStruct->FSMC_ECC = FSMC_ECC_Disable;
+ FSMC_NANDInitStruct->FSMC_ECCPageSize = FSMC_ECCPageSize_256Bytes;
+ FSMC_NANDInitStruct->FSMC_AddressLowMapping = FSMC_AddressLowMapping_Direct;
+ FSMC_NANDInitStruct->FSMC_TCLRSetupTime = 0x0;
+ FSMC_NANDInitStruct->FSMC_TARSetupTime = 0x0;
+ FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+ FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+ FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+ FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+ FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+ FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+ FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+ FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+}
+
+/*******************************************************************************
+* Function Name : FSMC_PCCARDStructInit
+* Description : Fills each FSMC_PCCARDInitStruct member with its default value.
+* Input : - FSMC_PCCARDInitStruct: pointer to a FSMC_PCCARDInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct)
+{
+ /* Reset PCCARD Init structure parameters values */
+ FSMC_PCCARDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable;
+ FSMC_PCCARDInitStruct->FSMC_AddressLowMapping = FSMC_AddressLowMapping_Direct;
+ FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime = 0x0;
+ FSMC_PCCARDInitStruct->FSMC_TARSetupTime = 0x0;
+ FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NORSRAMCmd
+* Description : Enables or disables the specified NOR/SRAM Memory Bank.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1
+* - FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2
+* - FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3
+* - FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4
+* : - NewState: new state of the FSMC_Bank.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NORSRAMCmd(u32 FSMC_Bank, FunctionalState NewState)
+{
+ assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected NOR/SRAM Bank by setting the PBKEN bit in the BCRx register */
+ FSMC_Bank1->BTCR[FSMC_Bank] |= BCR_MBKEN_Set;
+ }
+ else
+ {
+ /* Disable the selected NOR/SRAM Bank by clearing the PBKEN bit in the BCRx register */
+ FSMC_Bank1->BTCR[FSMC_Bank] &= BCR_MBKEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NANDCmd
+* Description : Enables or disables the specified NAND Memory Bank.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* : - NewState: new state of the FSMC_Bank.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NANDCmd(u32 FSMC_Bank, FunctionalState NewState)
+{
+ assert_param(IS_FSMC_NAND_BANK(FSMC_Bank));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected NAND Bank by setting the PBKEN bit in the PCRx register */
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ FSMC_Bank2->PCR2 |= PCR_PBKEN_Set;
+ }
+ else
+ {
+ FSMC_Bank3->PCR3 |= PCR_PBKEN_Set;
+ }
+ }
+ else
+ {
+ /* Disable the selected NAND Bank by clearing the PBKEN bit in the PCRx register */
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ FSMC_Bank2->PCR2 &= PCR_PBKEN_Reset;
+ }
+ else
+ {
+ FSMC_Bank3->PCR3 &= PCR_PBKEN_Reset;
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_PCCARDCmd
+* Description : Enables or disables the PCCARD Memory Bank.
+* Input : - NewState: new state of the PCCARD Memory Bank.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_PCCARDCmd(FunctionalState NewState)
+{
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the PCCARD Bank by setting the PBKEN bit in the PCR4 register */
+ FSMC_Bank4->PCR4 |= PCR_PBKEN_Set;
+ }
+ else
+ {
+ /* Disable the PCCARD Bank by clearing the PBKEN bit in the PCR4 register */
+ FSMC_Bank4->PCR4 &= PCR_PBKEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NANDECCCmd
+* Description : Enables or disables the FSMC NAND ECC feature.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* : - NewState: new state of the FSMC NAND ECC feature.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NANDECCCmd(u32 FSMC_Bank, FunctionalState NewState)
+{
+ assert_param(IS_FSMC_NAND_BANK(FSMC_Bank));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected NAND Bank ECC function by setting the ECCEN bit in the PCRx register */
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ FSMC_Bank2->PCR2 |= PCR_ECCEN_Set;
+ }
+ else
+ {
+ FSMC_Bank3->PCR3 |= PCR_ECCEN_Set;
+ }
+ }
+ else
+ {
+ /* Disable the selected NAND Bank ECC function by clearing the ECCEN bit in the PCRx register */
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ FSMC_Bank2->PCR2 &= PCR_ECCEN_Reset;
+ }
+ else
+ {
+ FSMC_Bank3->PCR3 &= PCR_ECCEN_Reset;
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_GetECC
+* Description : Returns the error correction code register value.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* Output : None
+* Return : The Error Correction Code (ECC) value.
+*******************************************************************************/
+u32 FSMC_GetECC(u32 FSMC_Bank)
+{
+ u32 eccval = 0x00000000;
+
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ /* Get the ECCR2 register value */
+ eccval = FSMC_Bank2->ECCR2;
+ }
+ else
+ {
+ /* Get the ECCR3 register value */
+ eccval = FSMC_Bank3->ECCR3;
+ }
+ /* Return the error correction code value */
+ return(eccval);
+}
+
+/*******************************************************************************
+* Function Name : FSMC_ITConfig
+* Description : Enables or disables the specified FSMC interrupts.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* - FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+* - FSMC_IT: specifies the FSMC interrupt sources to be
+* enabled or disabled.
+* This parameter can be any combination of the following values:
+* - FSMC_IT_RisingEdge: Rising edge detection interrupt.
+* - FSMC_IT_Level: Level edge detection interrupt.
+* - FSMC_IT_FallingEdge: Falling edge detection interrupt.
+* - NewState: new state of the specified FSMC interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_ITConfig(u32 FSMC_Bank, u32 FSMC_IT, FunctionalState NewState)
+{
+ assert_param(IS_FSMC_IT_BANK(FSMC_Bank));
+ assert_param(IS_FSMC_IT(FSMC_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected FSMC_Bank2 interrupts */
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ FSMC_Bank2->SR2 |= FSMC_IT;
+ }
+ /* Enable the selected FSMC_Bank3 interrupts */
+ else if (FSMC_Bank == FSMC_Bank3_NAND)
+ {
+ FSMC_Bank3->SR3 |= FSMC_IT;
+ }
+ /* Enable the selected FSMC_Bank4 interrupts */
+ else
+ {
+ FSMC_Bank4->SR4 |= FSMC_IT;
+ }
+ }
+ else
+ {
+ /* Disable the selected FSMC_Bank2 interrupts */
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+
+ FSMC_Bank2->SR2 &= (u32)~FSMC_IT;
+ }
+ /* Disable the selected FSMC_Bank3 interrupts */
+ else if (FSMC_Bank == FSMC_Bank3_NAND)
+ {
+ FSMC_Bank3->SR3 &= (u32)~FSMC_IT;
+ }
+ /* Disable the selected FSMC_Bank4 interrupts */
+ else
+ {
+ FSMC_Bank4->SR4 &= (u32)~FSMC_IT;
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_GetFlagStatus
+* Description : Checks whether the specified FSMC flag is set or not.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* - FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+* - FSMC_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - FSMC_FLAG_RisingEdge: Rising egde detection Flag.
+* - FSMC_FLAG_Level: Level detection Flag.
+* - FSMC_FLAG_FallingEdge: Falling egde detection Flag.
+* - FSMC_FLAG_FEMPT: Fifo empty Flag.
+* Output : None
+* Return : The new state of FSMC_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus FSMC_GetFlagStatus(u32 FSMC_Bank, u32 FSMC_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+ u32 tmpsr = 0x00000000;
+
+ /* Check the parameters */
+ assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank));
+ assert_param(IS_FSMC_GET_FLAG(FSMC_FLAG));
+
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ tmpsr = FSMC_Bank2->SR2;
+ }
+ else if(FSMC_Bank == FSMC_Bank3_NAND)
+ {
+ tmpsr = FSMC_Bank3->SR3;
+ }
+ /* FSMC_Bank4_PCCARD*/
+ else
+ {
+ tmpsr = FSMC_Bank4->SR4;
+ }
+
+ /* Get the flag status */
+ if ((tmpsr & FSMC_FLAG) != (u16)RESET )
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ /* Return the flag status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : FSMC_ClearFlag
+* Description : Clears the FSMC’s pending flags.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* - FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+* - FSMC_FLAG: specifies the flag to clear.
+* This parameter can be any combination of the following values:
+* - FSMC_FLAG_RisingEdge: Rising egde detection Flag.
+* - FSMC_FLAG_Level: Level detection Flag.
+* - FSMC_FLAG_FallingEdge: Falling egde detection Flag.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_ClearFlag(u32 FSMC_Bank, u32 FSMC_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank));
+ assert_param(IS_FSMC_CLEAR_FLAG(FSMC_FLAG)) ;
+
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ FSMC_Bank2->SR2 &= ~FSMC_FLAG;
+ }
+ else if(FSMC_Bank == FSMC_Bank3_NAND)
+ {
+ FSMC_Bank3->SR3 &= ~FSMC_FLAG;
+ }
+ /* FSMC_Bank4_PCCARD*/
+ else
+ {
+ FSMC_Bank4->SR4 &= ~FSMC_FLAG;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_GetITStatus
+* Description : Checks whether the specified FSMC interrupt has occurred or not.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* - FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+* - FSMC_IT: specifies the FSMC interrupt source to check.
+* This parameter can be one of the following values:
+* - FSMC_IT_RisingEdge: Rising edge detection interrupt.
+* - FSMC_IT_Level: Level edge detection interrupt.
+* - FSMC_IT_FallingEdge: Falling edge detection interrupt.
+* Output : None
+* Return : The new state of FSMC_IT (SET or RESET).
+*******************************************************************************/
+ITStatus FSMC_GetITStatus(u32 FSMC_Bank, u32 FSMC_IT)
+{
+ ITStatus bitstatus = RESET;
+ u32 tmpsr = 0x0, itstatus = 0x0, itenable = 0x0;
+
+ /* Check the parameters */
+ assert_param(IS_FSMC_IT_BANK(FSMC_Bank));
+ assert_param(IS_FSMC_GET_IT(FSMC_IT));
+
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ tmpsr = FSMC_Bank2->SR2;
+ }
+ else if(FSMC_Bank == FSMC_Bank3_NAND)
+ {
+ tmpsr = FSMC_Bank3->SR3;
+ }
+ /* FSMC_Bank4_PCCARD*/
+ else
+ {
+ tmpsr = FSMC_Bank4->SR4;
+ }
+
+ itstatus = tmpsr & FSMC_IT;
+
+ itenable = tmpsr & (FSMC_IT >> 3);
+
+ if ((itstatus != (u32)RESET) && (itenable != (u32)RESET))
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : FSMC_ClearITPendingBit
+* Description : Clears the FSMC’s interrupt pending bits.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* - FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+* - FSMC_IT: specifies the interrupt pending bit to clear.
+* This parameter can be any combination of the following values:
+* - FSMC_IT_RisingEdge: Rising edge detection interrupt.
+* - FSMC_IT_Level: Level edge detection interrupt.
+* - FSMC_IT_FallingEdge: Falling edge detection interrupt.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_ClearITPendingBit(u32 FSMC_Bank, u32 FSMC_IT)
+{
+ /* Check the parameters */
+ assert_param(IS_FSMC_IT_BANK(FSMC_Bank));
+ assert_param(IS_FSMC_IT(FSMC_IT));
+
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ FSMC_Bank2->SR2 &= ~(FSMC_IT >> 3);
+ }
+ else if(FSMC_Bank == FSMC_Bank3_NAND)
+ {
+ FSMC_Bank3->SR3 &= ~(FSMC_IT >> 3);
+ }
+ /* FSMC_Bank4_PCCARD*/
+ else
+ {
+ FSMC_Bank4->SR4 &= ~(FSMC_IT >> 3);
+ }
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_gpio.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_gpio.c new file mode 100755 index 0000000..9fbcd16 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_gpio.c @@ -0,0 +1,580 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_gpio.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the GPIO firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_gpio.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ------------ RCC registers bit address in the alias region ----------- */
+#define AFIO_OFFSET (AFIO_BASE - PERIPH_BASE)
+
+/* --- EVENTCR Register ---*/
+/* Alias word address of EVOE bit */
+#define EVCR_OFFSET (AFIO_OFFSET + 0x00)
+#define EVOE_BitNumber ((u8)0x07)
+#define EVCR_EVOE_BB (PERIPH_BB_BASE + (EVCR_OFFSET * 32) + (EVOE_BitNumber * 4))
+
+#define EVCR_PORTPINCONFIG_MASK ((u16)0xFF80)
+#define LSB_MASK ((u16)0xFFFF)
+#define DBGAFR_POSITION_MASK ((u32)0x000F0000)
+#define DBGAFR_SWJCFG_MASK ((u32)0xF0FFFFFF)
+#define DBGAFR_LOCATION_MASK ((u32)0x00200000)
+#define DBGAFR_NUMBITS_MASK ((u32)0x00100000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : GPIO_DeInit
+* Description : Deinitializes the GPIOx peripheral registers to their default
+* reset values.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_DeInit(GPIO_TypeDef* GPIOx)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+
+ switch (*(u32*)&GPIOx)
+ {
+ case GPIOA_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, DISABLE);
+ break;
+
+ case GPIOB_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, DISABLE);
+ break;
+
+ case GPIOC_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, DISABLE);
+ break;
+
+ case GPIOD_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, DISABLE);
+ break;
+
+ case GPIOE_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, DISABLE);
+ break;
+
+ case GPIOF_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, DISABLE);
+ break;
+
+ case GPIOG_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, DISABLE);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : GPIO_AFIODeInit
+* Description : Deinitializes the Alternate Functions (remap, event control
+* and EXTI configuration) registers to their default reset
+* values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_AFIODeInit(void)
+{
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, DISABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Init
+* Description : Initializes the GPIOx peripheral according to the specified
+* parameters in the GPIO_InitStruct.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* - GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure that
+* contains the configuration information for the specified GPIO
+* peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct)
+{
+ u32 currentmode = 0x00, currentpin = 0x00, pinpos = 0x00, pos = 0x00;
+ u32 tmpreg = 0x00, pinmask = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+ assert_param(IS_GPIO_MODE(GPIO_InitStruct->GPIO_Mode));
+ assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin));
+
+/*---------------------------- GPIO Mode Configuration -----------------------*/
+ currentmode = ((u32)GPIO_InitStruct->GPIO_Mode) & ((u32)0x0F);
+
+ if ((((u32)GPIO_InitStruct->GPIO_Mode) & ((u32)0x10)) != 0x00)
+ {
+ /* Check the parameters */
+ assert_param(IS_GPIO_SPEED(GPIO_InitStruct->GPIO_Speed));
+ /* Output mode */
+ currentmode |= (u32)GPIO_InitStruct->GPIO_Speed;
+ }
+
+/*---------------------------- GPIO CRL Configuration ------------------------*/
+ /* Configure the eight low port pins */
+ if (((u32)GPIO_InitStruct->GPIO_Pin & ((u32)0x00FF)) != 0x00)
+ {
+ tmpreg = GPIOx->CRL;
+
+ for (pinpos = 0x00; pinpos < 0x08; pinpos++)
+ {
+ pos = ((u32)0x01) << pinpos;
+ /* Get the port pins position */
+ currentpin = (GPIO_InitStruct->GPIO_Pin) & pos;
+
+ if (currentpin == pos)
+ {
+ pos = pinpos << 2;
+ /* Clear the corresponding low control register bits */
+ pinmask = ((u32)0x0F) << pos;
+ tmpreg &= ~pinmask;
+
+ /* Write the mode configuration in the corresponding bits */
+ tmpreg |= (currentmode << pos);
+
+ /* Reset the corresponding ODR bit */
+ if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD)
+ {
+ GPIOx->BRR = (((u32)0x01) << pinpos);
+ }
+ /* Set the corresponding ODR bit */
+ if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU)
+ {
+ GPIOx->BSRR = (((u32)0x01) << pinpos);
+ }
+ }
+ }
+ GPIOx->CRL = tmpreg;
+ }
+
+/*---------------------------- GPIO CRH Configuration ------------------------*/
+ /* Configure the eight high port pins */
+ if (GPIO_InitStruct->GPIO_Pin > 0x00FF)
+ {
+ tmpreg = GPIOx->CRH;
+ for (pinpos = 0x00; pinpos < 0x08; pinpos++)
+ {
+ pos = (((u32)0x01) << (pinpos + 0x08));
+ /* Get the port pins position */
+ currentpin = ((GPIO_InitStruct->GPIO_Pin) & pos);
+ if (currentpin == pos)
+ {
+ pos = pinpos << 2;
+ /* Clear the corresponding high control register bits */
+ pinmask = ((u32)0x0F) << pos;
+ tmpreg &= ~pinmask;
+
+ /* Write the mode configuration in the corresponding bits */
+ tmpreg |= (currentmode << pos);
+
+ /* Reset the corresponding ODR bit */
+ if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD)
+ {
+ GPIOx->BRR = (((u32)0x01) << (pinpos + 0x08));
+ }
+ /* Set the corresponding ODR bit */
+ if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU)
+ {
+ GPIOx->BSRR = (((u32)0x01) << (pinpos + 0x08));
+ }
+ }
+ }
+ GPIOx->CRH = tmpreg;
+ }
+}
+
+/*******************************************************************************
+* Function Name : GPIO_StructInit
+* Description : Fills each GPIO_InitStruct member with its default value.
+* Input : - GPIO_InitStruct : pointer to a GPIO_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct)
+{
+ /* Reset GPIO init structure parameters values */
+ GPIO_InitStruct->GPIO_Pin = GPIO_Pin_All;
+ GPIO_InitStruct->GPIO_Speed = GPIO_Speed_2MHz;
+ GPIO_InitStruct->GPIO_Mode = GPIO_Mode_IN_FLOATING;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_ReadInputDataBit
+* Description : Reads the specified input port pin.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* : - GPIO_Pin: specifies the port bit to read.
+* This parameter can be GPIO_Pin_x where x can be (0..15).
+* Output : None
+* Return : The input port pin value.
+*******************************************************************************/
+u8 GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin)
+{
+ u8 bitstatus = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+ assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
+
+ if ((GPIOx->IDR & GPIO_Pin) != (u32)Bit_RESET)
+ {
+ bitstatus = (u8)Bit_SET;
+ }
+ else
+ {
+ bitstatus = (u8)Bit_RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_ReadInputData
+* Description : Reads the specified GPIO input data port.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* Output : None
+* Return : GPIO input data port value.
+*******************************************************************************/
+u16 GPIO_ReadInputData(GPIO_TypeDef* GPIOx)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+
+ return ((u16)GPIOx->IDR);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_ReadOutputDataBit
+* Description : Reads the specified output data port bit.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* : - GPIO_Pin: specifies the port bit to read.
+* This parameter can be GPIO_Pin_x where x can be (0..15).
+* Output : None
+* Return : The output port pin value.
+*******************************************************************************/
+u8 GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin)
+{
+ u8 bitstatus = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+ assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
+
+ if ((GPIOx->ODR & GPIO_Pin) != (u32)Bit_RESET)
+ {
+ bitstatus = (u8)Bit_SET;
+ }
+ else
+ {
+ bitstatus = (u8)Bit_RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_ReadOutputData
+* Description : Reads the specified GPIO output data port.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* Output : None
+* Return : GPIO output data port value.
+*******************************************************************************/
+u16 GPIO_ReadOutputData(GPIO_TypeDef* GPIOx)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+
+ return ((u16)GPIOx->ODR);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_SetBits
+* Description : Sets the selected data port bits.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* - GPIO_Pin: specifies the port bits to be written.
+* This parameter can be any combination of GPIO_Pin_x where
+* x can be (0..15).
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_SetBits(GPIO_TypeDef* GPIOx, u16 GPIO_Pin)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+ assert_param(IS_GPIO_PIN(GPIO_Pin));
+
+ GPIOx->BSRR = GPIO_Pin;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_ResetBits
+* Description : Clears the selected data port bits.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* - GPIO_Pin: specifies the port bits to be written.
+* This parameter can be any combination of GPIO_Pin_x where
+* x can be (0..15).
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_ResetBits(GPIO_TypeDef* GPIOx, u16 GPIO_Pin)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+ assert_param(IS_GPIO_PIN(GPIO_Pin));
+
+ GPIOx->BRR = GPIO_Pin;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_WriteBit
+* Description : Sets or clears the selected data port bit.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* - GPIO_Pin: specifies the port bit to be written.
+* This parameter can be one of GPIO_Pin_x where x can be (0..15).
+* - BitVal: specifies the value to be written to the selected bit.
+* This parameter can be one of the BitAction enum values:
+* - Bit_RESET: to clear the port pin
+* - Bit_SET: to set the port pin
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_WriteBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin, BitAction BitVal)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+ assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
+ assert_param(IS_GPIO_BIT_ACTION(BitVal));
+
+ if (BitVal != Bit_RESET)
+ {
+ GPIOx->BSRR = GPIO_Pin;
+ }
+ else
+ {
+ GPIOx->BRR = GPIO_Pin;
+ }
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Write
+* Description : Writes data to the specified GPIO data port.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* - PortVal: specifies the value to be written to the port output
+* data register.
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Write(GPIO_TypeDef* GPIOx, u16 PortVal)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+
+ GPIOx->ODR = PortVal;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_PinLockConfig
+* Description : Locks GPIO Pins configuration registers.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* - GPIO_Pin: specifies the port bit to be written.
+* This parameter can be any combination of GPIO_Pin_x where
+* x can be (0..15).
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, u16 GPIO_Pin)
+{
+ u32 tmp = 0x00010000;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+ assert_param(IS_GPIO_PIN(GPIO_Pin));
+
+ tmp |= GPIO_Pin;
+ /* Set LCKK bit */
+ GPIOx->LCKR = tmp;
+ /* Reset LCKK bit */
+ GPIOx->LCKR = GPIO_Pin;
+ /* Set LCKK bit */
+ GPIOx->LCKR = tmp;
+ /* Read LCKK bit*/
+ tmp = GPIOx->LCKR;
+ /* Read LCKK bit*/
+ tmp = GPIOx->LCKR;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_EventOutputConfig
+* Description : Selects the GPIO pin used as Event output.
+* Input : - GPIO_PortSource: selects the GPIO port to be used as source
+* for Event output.
+* This parameter can be GPIO_PortSourceGPIOx where x can be
+* (A..E).
+* - GPIO_PinSource: specifies the pin for the Event output.
+* This parameter can be GPIO_PinSourcex where x can be (0..15).
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_EventOutputConfig(u8 GPIO_PortSource, u8 GPIO_PinSource)
+{
+ u32 tmpreg = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_EVENTOUT_PORT_SOURCE(GPIO_PortSource));
+ assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource));
+
+ tmpreg = AFIO->EVCR;
+ /* Clear the PORT[6:4] and PIN[3:0] bits */
+ tmpreg &= EVCR_PORTPINCONFIG_MASK;
+ tmpreg |= (u32)GPIO_PortSource << 0x04;
+ tmpreg |= GPIO_PinSource;
+
+ AFIO->EVCR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_EventOutputCmd
+* Description : Enables or disables the Event Output.
+* Input : - NewState: new state of the Event output.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_EventOutputCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) EVCR_EVOE_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_PinRemapConfig
+* Description : Changes the mapping of the specified pin.
+* Input : - GPIO_Remap: selects the pin to remap.
+* This parameter can be one of the following values:
+* - GPIO_Remap_SPI1
+* - GPIO_Remap_I2C1
+* - GPIO_Remap_USART1
+* - GPIO_Remap_USART2
+* - GPIO_PartialRemap_USART3
+* - GPIO_FullRemap_USART3
+* - GPIO_PartialRemap_TIM1
+* - GPIO_FullRemap_TIM1
+* - GPIO_PartialRemap1_TIM2
+* - GPIO_PartialRemap2_TIM2
+* - GPIO_FullRemap_TIM2
+* - GPIO_PartialRemap_TIM3
+* - GPIO_FullRemap_TIM3
+* - GPIO_Remap_TIM4
+* - GPIO_Remap1_CAN
+* - GPIO_Remap2_CAN
+* - GPIO_Remap_PD01
+* - GPIO_Remap_TIM5CH4_LSI
+* - GPIO_Remap_ADC1_ETRGINJ
+* - GPIO_Remap_ADC1_ETRGREG
+* - GPIO_Remap_ADC2_ETRGINJ
+* - GPIO_Remap_ADC2_ETRGREG
+* - GPIO_Remap_SWJ_NoJTRST
+* - GPIO_Remap_SWJ_JTAGDisable
+* - GPIO_Remap_SWJ_Disable
+* - NewState: new state of the port pin remapping.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_PinRemapConfig(u32 GPIO_Remap, FunctionalState NewState)
+{
+ u32 tmp = 0x00, tmp1 = 0x00, tmpreg = 0x00, tmpmask = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_REMAP(GPIO_Remap));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ tmpreg = AFIO->MAPR;
+
+ tmpmask = (GPIO_Remap & DBGAFR_POSITION_MASK) >> 0x10;
+ tmp = GPIO_Remap & LSB_MASK;
+
+ if ((GPIO_Remap & (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) == (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK))
+ {
+ tmpreg &= DBGAFR_SWJCFG_MASK;
+ AFIO->MAPR &= DBGAFR_SWJCFG_MASK;
+ }
+ else if ((GPIO_Remap & DBGAFR_NUMBITS_MASK) == DBGAFR_NUMBITS_MASK)
+ {
+ tmp1 = ((u32)0x03) << tmpmask;
+ tmpreg &= ~tmp1;
+ tmpreg |= ~DBGAFR_SWJCFG_MASK;
+ }
+ else
+ {
+ tmpreg &= ~(tmp << ((GPIO_Remap >> 0x15)*0x10));
+ tmpreg |= ~DBGAFR_SWJCFG_MASK;
+ }
+
+ if (NewState != DISABLE)
+ {
+ tmpreg |= (tmp << ((GPIO_Remap >> 0x15)*0x10));
+ }
+
+ AFIO->MAPR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_EXTILineConfig
+* Description : Selects the GPIO pin used as EXTI Line.
+* Input : - GPIO_PortSource: selects the GPIO port to be used as
+* source for EXTI lines.
+* This parameter can be GPIO_PortSourceGPIOx where x can be
+* (A..G).
+* - GPIO_PinSource: specifies the EXTI line to be configured.
+* This parameter can be GPIO_PinSourcex where x can be (0..15).
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_EXTILineConfig(u8 GPIO_PortSource, u8 GPIO_PinSource)
+{
+ u32 tmp = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_EXTI_PORT_SOURCE(GPIO_PortSource));
+ assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource));
+
+ tmp = ((u32)0x0F) << (0x04 * (GPIO_PinSource & (u8)0x03));
+
+ AFIO->EXTICR[GPIO_PinSource >> 0x02] &= ~tmp;
+ AFIO->EXTICR[GPIO_PinSource >> 0x02] |= (((u32)GPIO_PortSource) << (0x04 * (GPIO_PinSource & (u8)0x03)));
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_i2c.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_i2c.c new file mode 100755 index 0000000..8a26a69 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_i2c.c @@ -0,0 +1,1237 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_i2c.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the I2C firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_i2c.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* I2C SPE mask */
+#define CR1_PE_Set ((u16)0x0001)
+#define CR1_PE_Reset ((u16)0xFFFE)
+
+/* I2C START mask */
+#define CR1_START_Set ((u16)0x0100)
+#define CR1_START_Reset ((u16)0xFEFF)
+
+/* I2C STOP mask */
+#define CR1_STOP_Set ((u16)0x0200)
+#define CR1_STOP_Reset ((u16)0xFDFF)
+
+/* I2C ACK mask */
+#define CR1_ACK_Set ((u16)0x0400)
+#define CR1_ACK_Reset ((u16)0xFBFF)
+
+/* I2C ENGC mask */
+#define CR1_ENGC_Set ((u16)0x0040)
+#define CR1_ENGC_Reset ((u16)0xFFBF)
+
+/* I2C SWRST mask */
+#define CR1_SWRST_Set ((u16)0x8000)
+#define CR1_SWRST_Reset ((u16)0x7FFF)
+
+/* I2C PEC mask */
+#define CR1_PEC_Set ((u16)0x1000)
+#define CR1_PEC_Reset ((u16)0xEFFF)
+
+/* I2C ENPEC mask */
+#define CR1_ENPEC_Set ((u16)0x0020)
+#define CR1_ENPEC_Reset ((u16)0xFFDF)
+
+/* I2C ENARP mask */
+#define CR1_ENARP_Set ((u16)0x0010)
+#define CR1_ENARP_Reset ((u16)0xFFEF)
+
+/* I2C NOSTRETCH mask */
+#define CR1_NOSTRETCH_Set ((u16)0x0080)
+#define CR1_NOSTRETCH_Reset ((u16)0xFF7F)
+
+/* I2C registers Masks */
+#define CR1_CLEAR_Mask ((u16)0xFBF5)
+
+/* I2C DMAEN mask */
+#define CR2_DMAEN_Set ((u16)0x0800)
+#define CR2_DMAEN_Reset ((u16)0xF7FF)
+
+/* I2C LAST mask */
+#define CR2_LAST_Set ((u16)0x1000)
+#define CR2_LAST_Reset ((u16)0xEFFF)
+
+/* I2C FREQ mask */
+#define CR2_FREQ_Reset ((u16)0xFFC0)
+
+/* I2C ADD0 mask */
+#define OAR1_ADD0_Set ((u16)0x0001)
+#define OAR1_ADD0_Reset ((u16)0xFFFE)
+
+/* I2C ENDUAL mask */
+#define OAR2_ENDUAL_Set ((u16)0x0001)
+#define OAR2_ENDUAL_Reset ((u16)0xFFFE)
+
+/* I2C ADD2 mask */
+#define OAR2_ADD2_Reset ((u16)0xFF01)
+
+/* I2C F/S mask */
+#define CCR_FS_Set ((u16)0x8000)
+
+/* I2C CCR mask */
+#define CCR_CCR_Set ((u16)0x0FFF)
+
+/* I2C FLAG mask */
+#define FLAG_Mask ((u32)0x00FFFFFF)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : I2C_DeInit
+* Description : Deinitializes the I2Cx peripheral registers to their default
+* reset values.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_DeInit(I2C_TypeDef* I2Cx)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+ switch (*(u32*)&I2Cx)
+ {
+ case I2C1_BASE:
+ /* Enable I2C1 reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, ENABLE);
+ /* Release I2C1 from reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, DISABLE);
+ break;
+
+ case I2C2_BASE:
+ /* Enable I2C2 reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, ENABLE);
+ /* Release I2C2 from reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, DISABLE);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_Init
+* Description : Initializes the I2Cx peripheral according to the specified
+* parameters in the I2C_InitStruct.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_InitStruct: pointer to a I2C_InitTypeDef structure that
+* contains the configuration information for the specified
+* I2C peripheral.
+* Output : None
+* Return : None
+******************************************************************************/
+void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct)
+{
+ u16 tmpreg = 0, freqrange = 0;
+ u16 result = 0x04;
+ u32 pclk1 = 8000000;
+ RCC_ClocksTypeDef rcc_clocks;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_MODE(I2C_InitStruct->I2C_Mode));
+ assert_param(IS_I2C_DUTY_CYCLE(I2C_InitStruct->I2C_DutyCycle));
+ assert_param(IS_I2C_OWN_ADDRESS1(I2C_InitStruct->I2C_OwnAddress1));
+ assert_param(IS_I2C_ACK_STATE(I2C_InitStruct->I2C_Ack));
+ assert_param(IS_I2C_ACKNOWLEDGE_ADDRESS(I2C_InitStruct->I2C_AcknowledgedAddress));
+ assert_param(IS_I2C_CLOCK_SPEED(I2C_InitStruct->I2C_ClockSpeed));
+
+/*---------------------------- I2Cx CR2 Configuration ------------------------*/
+ /* Get the I2Cx CR2 value */
+ tmpreg = I2Cx->CR2;
+ /* Clear frequency FREQ[5:0] bits */
+ tmpreg &= CR2_FREQ_Reset;
+ /* Get pclk1 frequency value */
+ RCC_GetClocksFreq(&rcc_clocks);
+ pclk1 = rcc_clocks.PCLK1_Frequency;
+ /* Set frequency bits depending on pclk1 value */
+ freqrange = (u16)(pclk1 / 1000000);
+ tmpreg |= freqrange;
+ /* Write to I2Cx CR2 */
+ I2Cx->CR2 = tmpreg;
+
+/*---------------------------- I2Cx CCR Configuration ------------------------*/
+ /* Disable the selected I2C peripheral to configure TRISE */
+ I2Cx->CR1 &= CR1_PE_Reset;
+
+ /* Reset tmpreg value */
+ /* Clear F/S, DUTY and CCR[11:0] bits */
+ tmpreg = 0;
+
+ /* Configure speed in standard mode */
+ if (I2C_InitStruct->I2C_ClockSpeed <= 100000)
+ {
+ /* Standard mode speed calculate */
+ result = (u16)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed << 1));
+ /* Test if CCR value is under 0x4*/
+ if (result < 0x04)
+ {
+ /* Set minimum allowed value */
+ result = 0x04;
+ }
+ /* Set speed value for standard mode */
+ tmpreg |= result;
+ /* Set Maximum Rise Time for standard mode */
+ I2Cx->TRISE = freqrange + 1;
+ }
+ /* Configure speed in fast mode */
+ else /*(I2C_InitStruct->I2C_ClockSpeed <= 400000)*/
+ {
+ if (I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_2)
+ {
+ /* Fast mode speed calculate: Tlow/Thigh = 2 */
+ result = (u16)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 3));
+ }
+ else /*I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_16_9*/
+ {
+ /* Fast mode speed calculate: Tlow/Thigh = 16/9 */
+ result = (u16)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 25));
+ /* Set DUTY bit */
+ result |= I2C_DutyCycle_16_9;
+ }
+ /* Test if CCR value is under 0x1*/
+ if ((result & CCR_CCR_Set) == 0)
+ {
+ /* Set minimum allowed value */
+ result |= (u16)0x0001;
+ }
+ /* Set speed value and set F/S bit for fast mode */
+ tmpreg |= result | CCR_FS_Set;
+ /* Set Maximum Rise Time for fast mode */
+ I2Cx->TRISE = (u16)(((freqrange * 300) / 1000) + 1);
+ }
+ /* Write to I2Cx CCR */
+ I2Cx->CCR = tmpreg;
+
+ /* Enable the selected I2C peripheral */
+ I2Cx->CR1 |= CR1_PE_Set;
+
+/*---------------------------- I2Cx CR1 Configuration ------------------------*/
+ /* Get the I2Cx CR1 value */
+ tmpreg = I2Cx->CR1;
+ /* Clear ACK, SMBTYPE and SMBUS bits */
+ tmpreg &= CR1_CLEAR_Mask;
+ /* Configure I2Cx: mode and acknowledgement */
+ /* Set SMBTYPE and SMBUS bits according to I2C_Mode value */
+ /* Set ACK bit according to I2C_Ack value */
+ tmpreg |= (u16)((u32)I2C_InitStruct->I2C_Mode | I2C_InitStruct->I2C_Ack);
+ /* Write to I2Cx CR1 */
+ I2Cx->CR1 = tmpreg;
+
+/*---------------------------- I2Cx OAR1 Configuration -----------------------*/
+ /* Set I2Cx Own Address1 and acknowledged address */
+ I2Cx->OAR1 = (I2C_InitStruct->I2C_AcknowledgedAddress | I2C_InitStruct->I2C_OwnAddress1);
+}
+
+/*******************************************************************************
+* Function Name : I2C_StructInit
+* Description : Fills each I2C_InitStruct member with its default value.
+* Input : - I2C_InitStruct: pointer to an I2C_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct)
+{
+/*---------------- Reset I2C init structure parameters values ----------------*/
+ /* Initialize the I2C_Mode member */
+ I2C_InitStruct->I2C_Mode = I2C_Mode_I2C;
+
+ /* Initialize the I2C_DutyCycle member */
+ I2C_InitStruct->I2C_DutyCycle = I2C_DutyCycle_2;
+
+ /* Initialize the I2C_OwnAddress1 member */
+ I2C_InitStruct->I2C_OwnAddress1 = 0;
+
+ /* Initialize the I2C_Ack member */
+ I2C_InitStruct->I2C_Ack = I2C_Ack_Disable;
+
+ /* Initialize the I2C_AcknowledgedAddress member */
+ I2C_InitStruct->I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
+
+ /* initialize the I2C_ClockSpeed member */
+ I2C_InitStruct->I2C_ClockSpeed = 5000;
+}
+
+/*******************************************************************************
+* Function Name : I2C_Cmd
+* Description : Enables or disables the specified I2C peripheral.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2Cx peripheral. This parameter
+* can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected I2C peripheral */
+ I2Cx->CR1 |= CR1_PE_Set;
+ }
+ else
+ {
+ /* Disable the selected I2C peripheral */
+ I2Cx->CR1 &= CR1_PE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_DMACmd
+* Description : Enables or disables the specified I2C DMA requests.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C DMA transfer.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected I2C DMA requests */
+ I2Cx->CR2 |= CR2_DMAEN_Set;
+ }
+ else
+ {
+ /* Disable the selected I2C DMA requests */
+ I2Cx->CR2 &= CR2_DMAEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_DMALastTransferCmd
+* Description : Specifies that the next DMA transfer is the last one.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C DMA last transfer.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Next DMA transfer is the last transfer */
+ I2Cx->CR2 |= CR2_LAST_Set;
+ }
+ else
+ {
+ /* Next DMA transfer is not the last transfer */
+ I2Cx->CR2 &= CR2_LAST_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_GenerateSTART
+* Description : Generates I2Cx communication START condition.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C START condition generation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None.
+*******************************************************************************/
+void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Generate a START condition */
+ I2Cx->CR1 |= CR1_START_Set;
+ }
+ else
+ {
+ /* Disable the START condition generation */
+ I2Cx->CR1 &= CR1_START_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_GenerateSTOP
+* Description : Generates I2Cx communication STOP condition.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C STOP condition generation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None.
+*******************************************************************************/
+void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Generate a STOP condition */
+ I2Cx->CR1 |= CR1_STOP_Set;
+ }
+ else
+ {
+ /* Disable the STOP condition generation */
+ I2Cx->CR1 &= CR1_STOP_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_AcknowledgeConfig
+* Description : Enables or disables the specified I2C acknowledge feature.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C Acknowledgement.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None.
+*******************************************************************************/
+void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the acknowledgement */
+ I2Cx->CR1 |= CR1_ACK_Set;
+ }
+ else
+ {
+ /* Disable the acknowledgement */
+ I2Cx->CR1 &= CR1_ACK_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_OwnAddress2Config
+* Description : Configures the specified I2C own address2.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - Address: specifies the 7bit I2C own address2.
+* Output : None
+* Return : None.
+*******************************************************************************/
+void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, u8 Address)
+{
+ u16 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+ /* Get the old register value */
+ tmpreg = I2Cx->OAR2;
+ /* Reset I2Cx Own address2 bit [7:1] */
+ tmpreg &= OAR2_ADD2_Reset;
+ /* Set I2Cx Own address2 */
+ tmpreg |= (u16)(Address & (u16)0x00FE);
+ /* Store the new register value */
+ I2Cx->OAR2 = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : I2C_DualAddressCmd
+* Description : Enables or disables the specified I2C dual addressing mode.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C dual addressing mode.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable dual addressing mode */
+ I2Cx->OAR2 |= OAR2_ENDUAL_Set;
+ }
+ else
+ {
+ /* Disable dual addressing mode */
+ I2Cx->OAR2 &= OAR2_ENDUAL_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_GeneralCallCmd
+* Description : Enables or disables the specified I2C general call feature.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C General call.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable generall call */
+ I2Cx->CR1 |= CR1_ENGC_Set;
+ }
+ else
+ {
+ /* Disable generall call */
+ I2Cx->CR1 &= CR1_ENGC_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_ITConfig
+* Description : Enables or disables the specified I2C interrupts.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_IT: specifies the I2C interrupts sources to be enabled
+* or disabled.
+* This parameter can be any combination of the following values:
+* - I2C_IT_BUF: Buffer interrupt mask
+* - I2C_IT_EVT: Event interrupt mask
+* - I2C_IT_ERR: Error interrupt mask
+* - NewState: new state of the specified I2C interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_ITConfig(I2C_TypeDef* I2Cx, u16 I2C_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+ assert_param(IS_I2C_CONFIG_IT(I2C_IT));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected I2C interrupts */
+ I2Cx->CR2 |= I2C_IT;
+ }
+ else
+ {
+ /* Disable the selected I2C interrupts */
+ I2Cx->CR2 &= (u16)~I2C_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_SendData
+* Description : Sends a data byte through the I2Cx peripheral.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - Data: Byte to be transmitted..
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_SendData(I2C_TypeDef* I2Cx, u8 Data)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+ /* Write in the DR register the data to be sent */
+ I2Cx->DR = Data;
+}
+
+/*******************************************************************************
+* Function Name : I2C_ReceiveData
+* Description : Returns the most recent received data by the I2Cx peripheral.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* Output : None
+* Return : The value of the received data.
+*******************************************************************************/
+u8 I2C_ReceiveData(I2C_TypeDef* I2Cx)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+ /* Return the data in the DR register */
+ return (u8)I2Cx->DR;
+}
+
+/*******************************************************************************
+* Function Name : I2C_Send7bitAddress
+* Description : Transmits the address byte to select the slave device.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - Address: specifies the slave address which will be transmitted
+* - I2C_Direction: specifies whether the I2C device will be a
+* Transmitter or a Receiver.
+* This parameter can be one of the following values
+* - I2C_Direction_Transmitter: Transmitter mode
+* - I2C_Direction_Receiver: Receiver mode
+* Output : None
+* Return : None.
+*******************************************************************************/
+void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, u8 Address, u8 I2C_Direction)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_DIRECTION(I2C_Direction));
+
+ /* Test on the direction to set/reset the read/write bit */
+ if (I2C_Direction != I2C_Direction_Transmitter)
+ {
+ /* Set the address bit0 for read */
+ Address |= OAR1_ADD0_Set;
+ }
+ else
+ {
+ /* Reset the address bit0 for write */
+ Address &= OAR1_ADD0_Reset;
+ }
+ /* Send the address */
+ I2Cx->DR = Address;
+}
+
+/*******************************************************************************
+* Function Name : I2C_ReadRegister
+* Description : Reads the specified I2C register and returns its value.
+* Input1 : - I2C_Register: specifies the register to read.
+* This parameter can be one of the following values:
+* - I2C_Register_CR1: CR1 register.
+* - I2C_Register_CR2: CR2 register.
+* - I2C_Register_OAR1: OAR1 register.
+* - I2C_Register_OAR2: OAR2 register.
+* - I2C_Register_DR: DR register.
+* - I2C_Register_SR1: SR1 register.
+* - I2C_Register_SR2: SR2 register.
+* - I2C_Register_CCR: CCR register.
+* - I2C_Register_TRISE: TRISE register.
+* Output : None
+* Return : The value of the read register.
+*******************************************************************************/
+u16 I2C_ReadRegister(I2C_TypeDef* I2Cx, u8 I2C_Register)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_REGISTER(I2C_Register));
+
+ /* Return the selected register value */
+ return (*(vu16 *)(*((vu32 *)&I2Cx) + I2C_Register));
+}
+
+/*******************************************************************************
+* Function Name : I2C_SoftwareResetCmd
+* Description : Enables or disables the specified I2C software reset.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C software reset.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Peripheral under reset */
+ I2Cx->CR1 |= CR1_SWRST_Set;
+ }
+ else
+ {
+ /* Peripheral not under reset */
+ I2Cx->CR1 &= CR1_SWRST_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_SMBusAlertConfig
+* Description : Drives the SMBusAlert pin high or low for the specified I2C.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_SMBusAlert: specifies SMBAlert pin level.
+* This parameter can be one of the following values:
+* - I2C_SMBusAlert_Low: SMBAlert pin driven low
+* - I2C_SMBusAlert_High: SMBAlert pin driven high
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, u16 I2C_SMBusAlert)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_SMBUS_ALERT(I2C_SMBusAlert));
+
+ if (I2C_SMBusAlert == I2C_SMBusAlert_Low)
+ {
+ /* Drive the SMBusAlert pin Low */
+ I2Cx->CR1 |= I2C_SMBusAlert_Low;
+ }
+ else
+ {
+ /* Drive the SMBusAlert pin High */
+ I2Cx->CR1 &= I2C_SMBusAlert_High;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_TransmitPEC
+* Description : Enables or disables the specified I2C PEC transfer.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C PEC transmission.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected I2C PEC transmission */
+ I2Cx->CR1 |= CR1_PEC_Set;
+ }
+ else
+ {
+ /* Disable the selected I2C PEC transmission */
+ I2Cx->CR1 &= CR1_PEC_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_PECPositionConfig
+* Description : Selects the specified I2C PEC position.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_PECPosition: specifies the PEC position.
+* This parameter can be one of the following values:
+* - I2C_PECPosition_Next: indicates that the next
+* byte is PEC
+* - I2C_PECPosition_Current: indicates that current
+* byte is PEC
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, u16 I2C_PECPosition)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_PEC_POSITION(I2C_PECPosition));
+
+ if (I2C_PECPosition == I2C_PECPosition_Next)
+ {
+ /* Next byte in shift register is PEC */
+ I2Cx->CR1 |= I2C_PECPosition_Next;
+ }
+ else
+ {
+ /* Current byte in shift register is PEC */
+ I2Cx->CR1 &= I2C_PECPosition_Current;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_CalculatePEC
+* Description : Enables or disables the PEC value calculation of the
+* transfered bytes.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2Cx PEC value calculation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected I2C PEC calculation */
+ I2Cx->CR1 |= CR1_ENPEC_Set;
+ }
+ else
+ {
+ /* Disable the selected I2C PEC calculation */
+ I2Cx->CR1 &= CR1_ENPEC_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_GetPEC
+* Description : Returns the PEC value for the specified I2C.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* Output : None
+* Return : The PEC value.
+*******************************************************************************/
+u8 I2C_GetPEC(I2C_TypeDef* I2Cx)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+ /* Return the selected I2C PEC value */
+ return ((I2Cx->SR2) >> 8);
+}
+
+/*******************************************************************************
+* Function Name : I2C_ARPCmd
+* Description : Enables or disables the specified I2C ARP.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2Cx ARP.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected I2C ARP */
+ I2Cx->CR1 |= CR1_ENARP_Set;
+ }
+ else
+ {
+ /* Disable the selected I2C ARP */
+ I2Cx->CR1 &= CR1_ENARP_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_StretchClockCmd
+* Description : Enables or disables the specified I2C Clock stretching.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2Cx Clock stretching.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState == DISABLE)
+ {
+ /* Enable the selected I2C Clock stretching */
+ I2Cx->CR1 |= CR1_NOSTRETCH_Set;
+ }
+ else
+ {
+ /* Disable the selected I2C Clock stretching */
+ I2Cx->CR1 &= CR1_NOSTRETCH_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_FastModeDutyCycleConfig
+* Description : Selects the specified I2C fast mode duty cycle.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_DutyCycle: specifies the fast mode duty cycle.
+* This parameter can be one of the following values:
+* - I2C_DutyCycle_2: I2C fast mode Tlow/Thigh = 2
+* - I2C_DutyCycle_16_9: I2C fast mode Tlow/Thigh = 16/9
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, u16 I2C_DutyCycle)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_DUTY_CYCLE(I2C_DutyCycle));
+
+ if (I2C_DutyCycle != I2C_DutyCycle_16_9)
+ {
+ /* I2C fast mode Tlow/Thigh=2 */
+ I2Cx->CCR &= I2C_DutyCycle_2;
+ }
+ else
+ {
+ /* I2C fast mode Tlow/Thigh=16/9 */
+ I2Cx->CCR |= I2C_DutyCycle_16_9;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_GetLastEvent
+* Description : Returns the last I2Cx Event.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* Output : None
+* Return : The last event
+*******************************************************************************/
+u32 I2C_GetLastEvent(I2C_TypeDef* I2Cx)
+{
+ u32 lastevent = 0;
+ u32 flag1 = 0, flag2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+ /* Read the I2Cx status register */
+ flag1 = I2Cx->SR1;
+ flag2 = I2Cx->SR2;
+ flag2 = flag2 << 16;
+
+ /* Get the last event value from I2C status register */
+ lastevent = (flag1 | flag2) & FLAG_Mask;
+
+ /* Return status */
+ return lastevent;
+}
+
+/*******************************************************************************
+* Function Name : I2C_CheckEvent
+* Description : Checks whether the last I2Cx Event is equal to the one passed
+* as parameter.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_EVENT: specifies the event to be checked.
+* This parameter can be one of the following values:
+* - I2C_EVENT_SLAVE_ADDRESS_MATCHED : EV1
+* - I2C_EVENT_SLAVE_BYTE_RECEIVED : EV2
+* - I2C_EVENT_SLAVE_BYTE_TRANSMITTED : EV3
+* - I2C_EVENT_SLAVE_ACK_FAILURE : EV3-2
+* - I2C_EVENT_MASTER_MODE_SELECT : EV5
+* - I2C_EVENT_MASTER_MODE_SELECTED : EV6
+* - I2C_EVENT_MASTER_BYTE_RECEIVED : EV7
+* - I2C_EVENT_MASTER_BYTE_TRANSMITTED : EV8
+* - I2C_EVENT_MASTER_MODE_ADDRESS10 : EV9
+* - I2C_EVENT_SLAVE_STOP_DETECTED : EV4
+* Output : None
+* Return : An ErrorStatus enumuration value:
+* - SUCCESS: Last event is equal to the I2C_EVENT
+* - ERROR: Last event is different from the I2C_EVENT
+*******************************************************************************/
+ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, u32 I2C_EVENT)
+{
+ u32 lastevent = 0;
+ u32 flag1 = 0, flag2 = 0;
+ ErrorStatus status = ERROR;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_EVENT(I2C_EVENT));
+
+ /* Read the I2Cx status register */
+ flag1 = I2Cx->SR1;
+ flag2 = I2Cx->SR2;
+ flag2 = flag2 << 16;
+
+ /* Get the last event value from I2C status register */
+ lastevent = (flag1 | flag2) & FLAG_Mask;
+
+ /* Check whether the last event is equal to I2C_EVENT */
+ if (lastevent == I2C_EVENT )
+ {
+ /* SUCCESS: last event is equal to I2C_EVENT */
+ status = SUCCESS;
+ }
+ else
+ {
+ /* ERROR: last event is different from I2C_EVENT */
+ status = ERROR;
+ }
+
+ /* Return status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : I2C_GetFlagStatus
+* Description : Checks whether the specified I2C flag is set or not.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - I2C_FLAG_DUALF: Dual flag (Slave mode)
+* - I2C_FLAG_SMBHOST: SMBus host header (Slave mode)
+* - I2C_FLAG_SMBDEFAULT: SMBus default header (Slave mode)
+* - I2C_FLAG_GENCALL: General call header flag (Slave mode)
+* - I2C_FLAG_TRA: Transmitter/Receiver flag
+* - I2C_FLAG_BUSY: Bus busy flag
+* - I2C_FLAG_MSL: Master/Slave flag
+* - I2C_FLAG_SMBALERT: SMBus Alert flag
+* - I2C_FLAG_TIMEOUT: Timeout or Tlow error flag
+* - I2C_FLAG_PECERR: PEC error in reception flag
+* - I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode)
+* - I2C_FLAG_AF: Acknowledge failure flag
+* - I2C_FLAG_ARLO: Arbitration lost flag (Master mode)
+* - I2C_FLAG_BERR: Bus error flag
+* - I2C_FLAG_TXE: Data register empty flag (Transmitter)
+* - I2C_FLAG_RXNE: Data register not empty (Receiver) flag
+* - I2C_FLAG_STOPF: Stop detection flag (Slave mode)
+* - I2C_FLAG_ADD10: 10-bit header sent flag (Master mode)
+* - I2C_FLAG_BTF: Byte transfer finished flag
+* - I2C_FLAG_ADDR: Address sent flag (Master mode) “ADSL”
+* Address matched flag (Slave mode)”ENDAD”
+* - I2C_FLAG_SB: Start bit flag (Master mode)
+* Output : None
+* Return : The new state of I2C_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, u32 I2C_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+ u32 i2cstatus = 0;
+ u32 flag1 = 0, flag2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_GET_FLAG(I2C_FLAG));
+
+ /* Read the I2Cx status register */
+ flag1 = I2Cx->SR1;
+ flag2 = I2Cx->SR2;
+ flag2 = (flag2 & FLAG_Mask) << 16;
+
+ /* Get the I2C status value */
+ i2cstatus = flag1 | flag2;
+
+ /* Get bit[23:0] of the flag */
+ I2C_FLAG &= FLAG_Mask;
+
+ /* Check the status of the specified I2C flag */
+ if ((i2cstatus & I2C_FLAG) != (u32)RESET)
+ {
+ /* I2C_FLAG is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* I2C_FLAG is reset */
+ bitstatus = RESET;
+ }
+ /* Return the I2C_FLAG status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : I2C_ClearFlag
+* Description : Clears the I2Cx's pending flags.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_FLAG: specifies the flag to clear.
+* This parameter can be one of the following values:
+* - I2C_FLAG_SMBALERT: SMBus Alert flag
+* - I2C_FLAG_TIMEOUT: Timeout or Tlow error flag
+* - I2C_FLAG_PECERR: PEC error in reception flag
+* - I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode)
+* - I2C_FLAG_AF: Acknowledge failure flag
+* - I2C_FLAG_ARLO: Arbitration lost flag (Master mode)
+* - I2C_FLAG_BERR: Bus error flag
+* - I2C_FLAG_STOPF: Stop detection flag (Slave mode)
+* - I2C_FLAG_ADD10: 10-bit header sent flag (Master mode)
+* - I2C_FLAG_BTF: Byte transfer finished flag
+* - I2C_FLAG_ADDR: Address sent flag (Master mode) “ADSL”
+* Address matched flag (Slave mode)”ENDAD”
+* - I2C_FLAG_SB: Start bit flag (Master mode)
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_ClearFlag(I2C_TypeDef* I2Cx, u32 I2C_FLAG)
+{
+ u32 flagpos = 0;
+ u32 flagindex = 0;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_CLEAR_FLAG(I2C_FLAG));
+
+ /* Get the I2C flag position */
+ flagpos = I2C_FLAG & FLAG_Mask;
+
+ /* Get the I2C flag index */
+ flagindex = I2C_FLAG >> 28;
+
+ /* Clear the flag by writing 0 */
+ if (flagindex == 1)
+ {
+ /* Clear the selected I2C flag */
+ I2Cx->SR1 = (u16)~flagpos;
+ }
+ /* Flags that need a read of the SR1 register to be cleared */
+ else if (flagindex == 2)
+ {
+ /* Read the SR1 register */
+ (void)I2Cx->SR1;
+ }
+ /* Flags that need a read of SR1 and a write on CR1 registers to be cleared */
+ else if (flagindex == 6)
+ {
+ /* Read the SR1 register */
+ (void)I2Cx->SR1;
+
+ /* Write on the CR1 register */
+ I2Cx->CR1 |= CR1_PE_Set;
+ }
+ /* Flags that need a read of SR1 and SR2 registers to be cleared */
+ else /*flagindex == 0xA*/
+ {
+ /* Read the SR1 register */
+ (void)I2Cx->SR1;
+
+ /* Read the SR2 register */
+ (void)I2Cx->SR2;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_GetITStatus
+* Description : Checks whether the specified I2C interrupt has occurred or not.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_IT: specifies the interrupt source to check.
+* This parameter can be one of the following values:
+* - I2C_IT_SMBALERT: SMBus Alert flag
+* - I2C_IT_TIMEOUT: Timeout or Tlow error flag
+* - I2C_IT_PECERR: PEC error in reception flag
+* - I2C_IT_OVR: Overrun/Underrun flag (Slave mode)
+* - I2C_IT_AF: Acknowledge failure flag
+* - I2C_IT_ARLO: Arbitration lost flag (Master mode)
+* - I2C_IT_BERR: Bus error flag
+* - I2C_IT_TXE: Data register empty flag (Transmitter)
+* - I2C_IT_RXNE: Data register not empty (Receiver) flag
+* - I2C_IT_STOPF: Stop detection flag (Slave mode)
+* - I2C_IT_ADD10: 10-bit header sent flag (Master mode)
+* - I2C_IT_BTF: Byte transfer finished flag
+* - I2C_IT_ADDR: Address sent flag (Master mode) “ADSL”
+* Address matched flag (Slave mode)”ENDAD”
+* - I2C_IT_SB: Start bit flag (Master mode)
+* Output : None
+* Return : The new state of I2C_IT (SET or RESET).
+*******************************************************************************/
+ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, u32 I2C_IT)
+{
+ ITStatus bitstatus = RESET;
+ u32 i2cstatus = 0;
+ u32 flag1 = 0, flag2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_GET_IT(I2C_IT));
+
+ /* Read the I2Cx status register */
+ flag1 = I2Cx->SR1;
+ flag2 = I2Cx->SR2;
+ flag2 = (flag2 & FLAG_Mask) << 16;
+
+ /* Get the I2C status value */
+ i2cstatus = flag1 | flag2;
+
+ /* Get bit[23:0] of the flag */
+ I2C_IT &= FLAG_Mask;
+
+ /* Check the status of the specified I2C flag */
+ if ((i2cstatus & I2C_IT) != (u32)RESET)
+ {
+ /* I2C_IT is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* I2C_IT is reset */
+ bitstatus = RESET;
+ }
+ /* Return the I2C_IT status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : I2C_ClearITPendingBit
+* Description : Clears the I2Cx’s interrupt pending bits.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_IT: specifies the interrupt pending bit to clear.
+* This parameter can be one of the following values:
+* - I2C_IT_SMBALERT: SMBus Alert flag
+* - I2C_IT_TIMEOUT: Timeout or Tlow error flag
+* - I2C_IT_PECERR: PEC error in reception flag
+* - I2C_IT_OVR: Overrun/Underrun flag (Slave mode)
+* - I2C_IT_AF: Acknowledge failure flag
+* - I2C_IT_ARLO: Arbitration lost flag (Master mode)
+* - I2C_IT_BERR: Bus error flag
+* - I2C_IT_STOPF: Stop detection flag (Slave mode)
+* - I2C_IT_ADD10: 10-bit header sent flag (Master mode)
+* - I2C_IT_BTF: Byte transfer finished flag
+* - I2C_IT_ADDR: Address sent flag (Master mode) “ADSL”
+* Address matched flag (Slave mode)”ENDAD”
+* - I2C_IT_SB: Start bit flag (Master mode)
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, u32 I2C_IT)
+{
+ u32 flagpos = 0;
+ u32 flagindex = 0;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_CLEAR_IT(I2C_IT));
+
+ /* Get the I2C flag position */
+ flagpos = I2C_IT & FLAG_Mask;
+
+ /* Get the I2C flag index */
+ flagindex = I2C_IT >> 28;
+
+ /* Clear the flag by writing 0 */
+ if (flagindex == 1)
+ {
+ /* Clear the selected I2C flag */
+ I2Cx->SR1 = (u16)~flagpos;
+ }
+ /* Flags that need a read of the SR1 register to be cleared */
+ else if (flagindex == 2)
+ {
+ /* Read the SR1 register */
+ (void)I2Cx->SR1;
+ }
+ /* Flags that need a read of SR1 and a write on CR1 registers to be cleared */
+ else if (flagindex == 6)
+ {
+ /* Read the SR1 register */
+ (void)I2Cx->SR1;
+
+ /* Write on the CR1 register */
+ I2Cx->CR1 |= CR1_PE_Set;
+ }
+ /* Flags that need a read of SR1 and SR2 registers to be cleared */
+ else /*flagindex == 0xA*/
+ {
+ /* Read the SR1 register */
+ (void)I2Cx->SR1;
+
+ /* Read the SR2 register */
+ (void)I2Cx->SR2;
+ }
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_iwdg.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_iwdg.c new file mode 100755 index 0000000..4c6143e --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_iwdg.c @@ -0,0 +1,148 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_iwdg.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the IWDG firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_iwdg.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ---------------------- IWDG registers bit mask ------------------------ */
+/* KR register bit mask */
+#define KR_KEY_Reload ((u16)0xAAAA)
+#define KR_KEY_Enable ((u16)0xCCCC)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : IWDG_WriteAccessCmd
+* Description : Enables or disables write access to IWDG_PR and IWDG_RLR
+* registers.
+* Input : - IWDG_WriteAccess: new state of write access to IWDG_PR and
+* IWDG_RLR registers.
+* This parameter can be one of the following values:
+* - IWDG_WriteAccess_Enable: Enable write access to
+* IWDG_PR and IWDG_RLR registers
+* - IWDG_WriteAccess_Disable: Disable write access to
+* IWDG_PR and IWDG_RLR registers
+* Output : None
+* Return : None
+*******************************************************************************/
+void IWDG_WriteAccessCmd(u16 IWDG_WriteAccess)
+{
+ /* Check the parameters */
+ assert_param(IS_IWDG_WRITE_ACCESS(IWDG_WriteAccess));
+
+ IWDG->KR = IWDG_WriteAccess;
+}
+
+/*******************************************************************************
+* Function Name : IWDG_SetPrescaler
+* Description : Sets IWDG Prescaler value.
+* Input : - IWDG_Prescaler: specifies the IWDG Prescaler value.
+* This parameter can be one of the following values:
+* - IWDG_Prescaler_4: IWDG prescaler set to 4
+* - IWDG_Prescaler_8: IWDG prescaler set to 8
+* - IWDG_Prescaler_16: IWDG prescaler set to 16
+* - IWDG_Prescaler_32: IWDG prescaler set to 32
+* - IWDG_Prescaler_64: IWDG prescaler set to 64
+* - IWDG_Prescaler_128: IWDG prescaler set to 128
+* - IWDG_Prescaler_256: IWDG prescaler set to 256
+* Output : None
+* Return : None
+*******************************************************************************/
+void IWDG_SetPrescaler(u8 IWDG_Prescaler)
+{
+ /* Check the parameters */
+ assert_param(IS_IWDG_PRESCALER(IWDG_Prescaler));
+
+ IWDG->PR = IWDG_Prescaler;
+}
+
+/*******************************************************************************
+* Function Name : IWDG_SetReload
+* Description : Sets IWDG Reload value.
+* Input : - Reload: specifies the IWDG Reload value.
+* This parameter must be a number between 0 and 0x0FFF.
+* Output : None
+* Return : None
+*******************************************************************************/
+void IWDG_SetReload(u16 Reload)
+{
+ /* Check the parameters */
+ assert_param(IS_IWDG_RELOAD(Reload));
+
+ IWDG->RLR = Reload;
+}
+
+/*******************************************************************************
+* Function Name : IWDG_ReloadCounter
+* Description : Reloads IWDG counter with value defined in the reload register
+* (write access to IWDG_PR and IWDG_RLR registers disabled).
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void IWDG_ReloadCounter(void)
+{
+ IWDG->KR = KR_KEY_Reload;
+}
+
+/*******************************************************************************
+* Function Name : IWDG_Enable
+* Description : Enables IWDG (write access to IWDG_PR and IWDG_RLR registers
+* disabled).
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void IWDG_Enable(void)
+{
+ IWDG->KR = KR_KEY_Enable;
+}
+
+/*******************************************************************************
+* Function Name : IWDG_GetFlagStatus
+* Description : Checks whether the specified IWDG flag is set or not.
+* Input : - IWDG_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - IWDG_FLAG_PVU: Prescaler Value Update on going
+* - IWDG_FLAG_RVU: Reload Value Update on going
+* Output : None
+* Return : The new state of IWDG_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus IWDG_GetFlagStatus(u16 IWDG_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_IWDG_FLAG(IWDG_FLAG));
+
+ if ((IWDG->SR & IWDG_FLAG) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+
+ /* Return the flag status */
+ return bitstatus;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_lib.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_lib.c new file mode 100755 index 0000000..988ac9f --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_lib.c @@ -0,0 +1,303 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_lib.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all peripherals pointers initialization.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+#define EXT
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : debug
+* Description : This function initialize peripherals pointers.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void debug(void)
+{
+
+/************************************* ADC ************************************/
+#ifdef _ADC1
+ ADC1 = (ADC_TypeDef *) ADC1_BASE;
+#endif /*_ADC1 */
+
+#ifdef _ADC2
+ ADC2 = (ADC_TypeDef *) ADC2_BASE;
+#endif /*_ADC2 */
+
+#ifdef _ADC3
+ ADC3 = (ADC_TypeDef *) ADC3_BASE;
+#endif /*_ADC3 */
+
+/************************************* BKP ************************************/
+#ifdef _BKP
+ BKP = (BKP_TypeDef *) BKP_BASE;
+#endif /*_BKP */
+
+/************************************* CAN ************************************/
+#ifdef _CAN
+ CAN = (CAN_TypeDef *) CAN_BASE;
+#endif /*_CAN */
+
+/************************************* CRC ************************************/
+#ifdef _CRC
+ CRC = (CRC_TypeDef *) CRC_BASE;
+#endif /*_CRC */
+
+/************************************* DAC ************************************/
+#ifdef _DAC
+ DAC = (DAC_TypeDef *) DAC_BASE;
+#endif /*_DAC */
+
+/************************************* DBGMCU**********************************/
+#ifdef _DBGMCU
+ DBGMCU = (DBGMCU_TypeDef *) DBGMCU_BASE;
+#endif /*_DBGMCU */
+
+/************************************* DMA ************************************/
+#ifdef _DMA
+ DMA1 = (DMA_TypeDef *) DMA1_BASE;
+ DMA2 = (DMA_TypeDef *) DMA2_BASE;
+#endif /*_DMA */
+
+#ifdef _DMA1_Channel1
+ DMA1_Channel1 = (DMA_Channel_TypeDef *) DMA1_Channel1_BASE;
+#endif /*_DMA1_Channel1 */
+
+#ifdef _DMA1_Channel2
+ DMA1_Channel2 = (DMA_Channel_TypeDef *) DMA1_Channel2_BASE;
+#endif /*_DMA1_Channel2 */
+
+#ifdef _DMA1_Channel3
+ DMA1_Channel3 = (DMA_Channel_TypeDef *) DMA1_Channel3_BASE;
+#endif /*_DMA1_Channel3 */
+
+#ifdef _DMA1_Channel4
+ DMA1_Channel4 = (DMA_Channel_TypeDef *) DMA1_Channel4_BASE;
+#endif /*_DMA1_Channel4 */
+
+#ifdef _DMA1_Channel5
+ DMA1_Channel5 = (DMA_Channel_TypeDef *) DMA1_Channel5_BASE;
+#endif /*_DMA1_Channel5 */
+
+#ifdef _DMA1_Channel6
+ DMA1_Channel6 = (DMA_Channel_TypeDef *) DMA1_Channel6_BASE;
+#endif /*_DMA1_Channel6 */
+
+#ifdef _DMA1_Channel7
+ DMA1_Channel7 = (DMA_Channel_TypeDef *) DMA1_Channel7_BASE;
+#endif /*_DMA1_Channel7 */
+
+#ifdef _DMA2_Channel1
+ DMA2_Channel1 = (DMA_Channel_TypeDef *) DMA2_Channel1_BASE;
+#endif /*_DMA2_Channel1 */
+
+#ifdef _DMA2_Channel2
+ DMA2_Channel2 = (DMA_Channel_TypeDef *) DMA2_Channel2_BASE;
+#endif /*_DMA2_Channel2 */
+
+#ifdef _DMA2_Channel3
+ DMA2_Channel3 = (DMA_Channel_TypeDef *) DMA2_Channel3_BASE;
+#endif /*_DMA2_Channel3 */
+
+#ifdef _DMA2_Channel4
+ DMA2_Channel4 = (DMA_Channel_TypeDef *) DMA2_Channel4_BASE;
+#endif /*_DMA2_Channel4 */
+
+#ifdef _DMA2_Channel5
+ DMA2_Channel5 = (DMA_Channel_TypeDef *) DMA2_Channel5_BASE;
+#endif /*_DMA2_Channel5 */
+
+/************************************* EXTI ***********************************/
+#ifdef _EXTI
+ EXTI = (EXTI_TypeDef *) EXTI_BASE;
+#endif /*_EXTI */
+
+/************************************* FLASH and Option Bytes *****************/
+#ifdef _FLASH
+ FLASH = (FLASH_TypeDef *) FLASH_R_BASE;
+ OB = (OB_TypeDef *) OB_BASE;
+#endif /*_FLASH */
+
+/************************************* FSMC ***********************************/
+#ifdef _FSMC
+ FSMC_Bank1 = (FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE;
+ FSMC_Bank1E = (FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE;
+ FSMC_Bank2 = (FSMC_Bank2_TypeDef *) FSMC_Bank2_R_BASE;
+ FSMC_Bank3 = (FSMC_Bank3_TypeDef *) FSMC_Bank3_R_BASE;
+ FSMC_Bank4 = (FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE;
+#endif /*_FSMC */
+
+/************************************* GPIO ***********************************/
+#ifdef _GPIOA
+ GPIOA = (GPIO_TypeDef *) GPIOA_BASE;
+#endif /*_GPIOA */
+
+#ifdef _GPIOB
+ GPIOB = (GPIO_TypeDef *) GPIOB_BASE;
+#endif /*_GPIOB */
+
+#ifdef _GPIOC
+ GPIOC = (GPIO_TypeDef *) GPIOC_BASE;
+#endif /*_GPIOC */
+
+#ifdef _GPIOD
+ GPIOD = (GPIO_TypeDef *) GPIOD_BASE;
+#endif /*_GPIOD */
+
+#ifdef _GPIOE
+ GPIOE = (GPIO_TypeDef *) GPIOE_BASE;
+#endif /*_GPIOE */
+
+#ifdef _GPIOF
+ GPIOF = (GPIO_TypeDef *) GPIOF_BASE;
+#endif /*_GPIOF */
+
+#ifdef _GPIOG
+ GPIOG = (GPIO_TypeDef *) GPIOG_BASE;
+#endif /*_GPIOG */
+
+#ifdef _AFIO
+ AFIO = (AFIO_TypeDef *) AFIO_BASE;
+#endif /*_AFIO */
+
+/************************************* I2C ************************************/
+#ifdef _I2C1
+ I2C1 = (I2C_TypeDef *) I2C1_BASE;
+#endif /*_I2C1 */
+
+#ifdef _I2C2
+ I2C2 = (I2C_TypeDef *) I2C2_BASE;
+#endif /*_I2C2 */
+
+/************************************* IWDG ***********************************/
+#ifdef _IWDG
+ IWDG = (IWDG_TypeDef *) IWDG_BASE;
+#endif /*_IWDG */
+
+/************************************* NVIC ***********************************/
+#ifdef _NVIC
+ NVIC = (NVIC_TypeDef *) NVIC_BASE;
+ SCB = (SCB_TypeDef *) SCB_BASE;
+#endif /*_NVIC */
+
+/************************************* PWR ************************************/
+#ifdef _PWR
+ PWR = (PWR_TypeDef *) PWR_BASE;
+#endif /*_PWR */
+
+/************************************* RCC ************************************/
+#ifdef _RCC
+ RCC = (RCC_TypeDef *) RCC_BASE;
+#endif /*_RCC */
+
+/************************************* RTC ************************************/
+#ifdef _RTC
+ RTC = (RTC_TypeDef *) RTC_BASE;
+#endif /*_RTC */
+
+/************************************* SDIO ***********************************/
+#ifdef _SDIO
+ SDIO = (SDIO_TypeDef *) SDIO_BASE;
+#endif /*_SDIO */
+
+/************************************* SPI ************************************/
+#ifdef _SPI1
+ SPI1 = (SPI_TypeDef *) SPI1_BASE;
+#endif /*_SPI1 */
+
+#ifdef _SPI2
+ SPI2 = (SPI_TypeDef *) SPI2_BASE;
+#endif /*_SPI2 */
+
+#ifdef _SPI3
+ SPI3 = (SPI_TypeDef *) SPI3_BASE;
+#endif /*_SPI3 */
+
+/************************************* SysTick ********************************/
+#ifdef _SysTick
+ SysTick = (SysTick_TypeDef *) SysTick_BASE;
+#endif /*_SysTick */
+
+/************************************* TIM ************************************/
+#ifdef _TIM1
+ TIM1 = (TIM_TypeDef *) TIM1_BASE;
+#endif /*_TIM1 */
+
+#ifdef _TIM2
+ TIM2 = (TIM_TypeDef *) TIM2_BASE;
+#endif /*_TIM2 */
+
+#ifdef _TIM3
+ TIM3 = (TIM_TypeDef *) TIM3_BASE;
+#endif /*_TIM3 */
+
+#ifdef _TIM4
+ TIM4 = (TIM_TypeDef *) TIM4_BASE;
+#endif /*_TIM4 */
+
+#ifdef _TIM5
+ TIM5 = (TIM_TypeDef *) TIM5_BASE;
+#endif /*_TIM5 */
+
+#ifdef _TIM6
+ TIM6 = (TIM_TypeDef *) TIM6_BASE;
+#endif /*_TIM6 */
+
+#ifdef _TIM7
+ TIM7 = (TIM_TypeDef *) TIM7_BASE;
+#endif /*_TIM7 */
+
+#ifdef _TIM8
+ TIM8 = (TIM_TypeDef *) TIM8_BASE;
+#endif /*_TIM8 */
+
+/************************************* USART **********************************/
+#ifdef _USART1
+ USART1 = (USART_TypeDef *) USART1_BASE;
+#endif /*_USART1 */
+
+#ifdef _USART2
+ USART2 = (USART_TypeDef *) USART2_BASE;
+#endif /*_USART2 */
+
+#ifdef _USART3
+ USART3 = (USART_TypeDef *) USART3_BASE;
+#endif /*_USART3 */
+
+#ifdef _UART4
+ UART4 = (USART_TypeDef *) UART4_BASE;
+#endif /*_UART4 */
+
+#ifdef _UART5
+ UART5 = (USART_TypeDef *) UART5_BASE;
+#endif /*_UART5 */
+
+/************************************* WWDG ***********************************/
+#ifdef _WWDG
+ WWDG = (WWDG_TypeDef *) WWDG_BASE;
+#endif /*_WWDG */
+}
+#endif /* DEBUG*/
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_nvic.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_nvic.c new file mode 100755 index 0000000..272c2cd --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_nvic.c @@ -0,0 +1,751 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_nvic.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the NVIC firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_nvic.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define AIRCR_VECTKEY_MASK ((u32)0x05FA0000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NVIC_DeInit
+* Description : Deinitializes the NVIC peripheral registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_DeInit(void)
+{
+ u32 index = 0;
+
+ NVIC->ICER[0] = 0xFFFFFFFF;
+ NVIC->ICER[1] = 0x0FFFFFFF;
+ NVIC->ICPR[0] = 0xFFFFFFFF;
+ NVIC->ICPR[1] = 0x0FFFFFFF;
+
+ for(index = 0; index < 0x0F; index++)
+ {
+ NVIC->IPR[index] = 0x00000000;
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SCBDeInit
+* Description : Deinitializes the SCB peripheral registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SCBDeInit(void)
+{
+ u32 index = 0x00;
+
+ SCB->ICSR = 0x0A000000;
+ SCB->VTOR = 0x00000000;
+ SCB->AIRCR = AIRCR_VECTKEY_MASK;
+ SCB->SCR = 0x00000000;
+ SCB->CCR = 0x00000000;
+ for(index = 0; index < 0x03; index++)
+ {
+ SCB->SHPR[index] = 0;
+ }
+ SCB->SHCSR = 0x00000000;
+ SCB->CFSR = 0xFFFFFFFF;
+ SCB->HFSR = 0xFFFFFFFF;
+ SCB->DFSR = 0xFFFFFFFF;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_PriorityGroupConfig
+* Description : Configures the priority grouping: pre-emption priority
+* and subpriority.
+* Input : - NVIC_PriorityGroup: specifies the priority grouping bits
+* length. This parameter can be one of the following values:
+* - NVIC_PriorityGroup_0: 0 bits for pre-emption priority
+* 4 bits for subpriority
+* - NVIC_PriorityGroup_1: 1 bits for pre-emption priority
+* 3 bits for subpriority
+* - NVIC_PriorityGroup_2: 2 bits for pre-emption priority
+* 2 bits for subpriority
+* - NVIC_PriorityGroup_3: 3 bits for pre-emption priority
+* 1 bits for subpriority
+* - NVIC_PriorityGroup_4: 4 bits for pre-emption priority
+* 0 bits for subpriority
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_PriorityGroupConfig(u32 NVIC_PriorityGroup)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_PRIORITY_GROUP(NVIC_PriorityGroup));
+
+ /* Set the PRIGROUP[10:8] bits according to NVIC_PriorityGroup value */
+ SCB->AIRCR = AIRCR_VECTKEY_MASK | NVIC_PriorityGroup;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Init
+* Description : Initializes the NVIC peripheral according to the specified
+* parameters in the NVIC_InitStruct.
+* Input : - NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure
+* that contains the configuration information for the
+* specified NVIC peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct)
+{
+ u32 tmppriority = 0x00, tmpreg = 0x00, tmpmask = 0x00;
+ u32 tmppre = 0, tmpsub = 0x0F;
+
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NVIC_InitStruct->NVIC_IRQChannelCmd));
+ assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_InitStruct->NVIC_IRQChannel));
+ assert_param(IS_NVIC_PREEMPTION_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority));
+ assert_param(IS_NVIC_SUB_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelSubPriority));
+
+ if (NVIC_InitStruct->NVIC_IRQChannelCmd != DISABLE)
+ {
+ /* Compute the Corresponding IRQ Priority --------------------------------*/
+ tmppriority = (0x700 - (SCB->AIRCR & (u32)0x700))>> 0x08;
+ tmppre = (0x4 - tmppriority);
+ tmpsub = tmpsub >> tmppriority;
+
+ tmppriority = (u32)NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority << tmppre;
+ tmppriority |= NVIC_InitStruct->NVIC_IRQChannelSubPriority & tmpsub;
+
+ tmppriority = tmppriority << 0x04;
+ tmppriority = ((u32)tmppriority) << ((NVIC_InitStruct->NVIC_IRQChannel & (u8)0x03) * 0x08);
+
+ tmpreg = NVIC->IPR[(NVIC_InitStruct->NVIC_IRQChannel >> 0x02)];
+ tmpmask = (u32)0xFF << ((NVIC_InitStruct->NVIC_IRQChannel & (u8)0x03) * 0x08);
+ tmpreg &= ~tmpmask;
+ tmppriority &= tmpmask;
+ tmpreg |= tmppriority;
+
+ NVIC->IPR[(NVIC_InitStruct->NVIC_IRQChannel >> 0x02)] = tmpreg;
+
+ /* Enable the Selected IRQ Channels --------------------------------------*/
+ NVIC->ISER[(NVIC_InitStruct->NVIC_IRQChannel >> 0x05)] =
+ (u32)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (u8)0x1F);
+ }
+ else
+ {
+ /* Disable the Selected IRQ Channels -------------------------------------*/
+ NVIC->ICER[(NVIC_InitStruct->NVIC_IRQChannel >> 0x05)] =
+ (u32)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (u8)0x1F);
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_StructInit
+* Description : Fills each NVIC_InitStruct member with its default value.
+* Input : - NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure which
+* will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_StructInit(NVIC_InitTypeDef* NVIC_InitStruct)
+{
+ /* NVIC_InitStruct members default value */
+ NVIC_InitStruct->NVIC_IRQChannel = 0x00;
+ NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority = 0x00;
+ NVIC_InitStruct->NVIC_IRQChannelSubPriority = 0x00;
+ NVIC_InitStruct->NVIC_IRQChannelCmd = DISABLE;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SETPRIMASK
+* Description : Enables the PRIMASK priority: Raises the execution priority to 0.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SETPRIMASK(void)
+{
+ __SETPRIMASK();
+}
+
+/*******************************************************************************
+* Function Name : NVIC_RESETPRIMASK
+* Description : Disables the PRIMASK priority.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_RESETPRIMASK(void)
+{
+ __RESETPRIMASK();
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SETFAULTMASK
+* Description : Enables the FAULTMASK priority: Raises the execution priority to -1.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SETFAULTMASK(void)
+{
+ __SETFAULTMASK();
+}
+
+/*******************************************************************************
+* Function Name : NVIC_RESETFAULTMASK
+* Description : Disables the FAULTMASK priority.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_RESETFAULTMASK(void)
+{
+ __RESETFAULTMASK();
+}
+
+/*******************************************************************************
+* Function Name : NVIC_BASEPRICONFIG
+* Description : The execution priority can be changed from 15 (lowest
+ configurable priority) to 1. Writing a zero value will disable
+* the mask of execution priority.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_BASEPRICONFIG(u32 NewPriority)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_BASE_PRI(NewPriority));
+
+ __BASEPRICONFIG(NewPriority << 0x04);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetBASEPRI
+* Description : Returns the BASEPRI mask value.
+* Input : None
+* Output : None
+* Return : BASEPRI register value
+*******************************************************************************/
+u32 NVIC_GetBASEPRI(void)
+{
+ return (__GetBASEPRI());
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetCurrentPendingIRQChannel
+* Description : Returns the current pending IRQ channel identifier.
+* Input : None
+* Output : None
+* Return : Pending IRQ Channel Identifier.
+*******************************************************************************/
+u16 NVIC_GetCurrentPendingIRQChannel(void)
+{
+ return ((u16)((SCB->ICSR & (u32)0x003FF000) >> 0x0C));
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetIRQChannelPendingBitStatus
+* Description : Checks whether the specified IRQ Channel pending bit is set
+* or not.
+* Input : - NVIC_IRQChannel: specifies the interrupt pending bit to check.
+* Output : None
+* Return : The new state of IRQ Channel pending bit(SET or RESET).
+*******************************************************************************/
+ITStatus NVIC_GetIRQChannelPendingBitStatus(u8 NVIC_IRQChannel)
+{
+ ITStatus pendingirqstatus = RESET;
+ u32 tmp = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_IRQChannel));
+
+ tmp = ((u32)0x01 << (NVIC_IRQChannel & (u32)0x1F));
+
+ if (((NVIC->ISPR[(NVIC_IRQChannel >> 0x05)]) & tmp) == tmp)
+ {
+ pendingirqstatus = SET;
+ }
+ else
+ {
+ pendingirqstatus = RESET;
+ }
+ return pendingirqstatus;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SetIRQChannelPendingBit
+* Description : Sets the NVIC’s interrupt pending bit.
+* Input : - NVIC_IRQChannel: specifies the interrupt pending bit to Set.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SetIRQChannelPendingBit(u8 NVIC_IRQChannel)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_IRQChannel));
+
+ *(vu32*) 0xE000EF00 = (u32)NVIC_IRQChannel;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_ClearIRQChannelPendingBit
+* Description : Clears the NVIC’s interrupt pending bit.
+* Input : - NVIC_IRQChannel: specifies the interrupt pending bit to clear.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_ClearIRQChannelPendingBit(u8 NVIC_IRQChannel)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_IRQChannel));
+
+ NVIC->ICPR[(NVIC_IRQChannel >> 0x05)] = (u32)0x01 << (NVIC_IRQChannel & (u32)0x1F);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetCurrentActiveHandler
+* Description : Returns the current active Handler (IRQ Channel and
+* SystemHandler) identifier.
+* Input : None
+* Output : None
+* Return : Active Handler Identifier.
+*******************************************************************************/
+u16 NVIC_GetCurrentActiveHandler(void)
+{
+ return ((u16)(SCB->ICSR & (u32)0x3FF));
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetIRQChannelActiveBitStatus
+* Description : Checks whether the specified IRQ Channel active bit is set
+* or not.
+* Input : - NVIC_IRQChannel: specifies the interrupt active bit to check.
+* Output : None
+* Return : The new state of IRQ Channel active bit(SET or RESET).
+*******************************************************************************/
+ITStatus NVIC_GetIRQChannelActiveBitStatus(u8 NVIC_IRQChannel)
+{
+ ITStatus activeirqstatus = RESET;
+ u32 tmp = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_IRQChannel));
+
+ tmp = ((u32)0x01 << (NVIC_IRQChannel & (u32)0x1F));
+
+ if (((NVIC->IABR[(NVIC_IRQChannel >> 0x05)]) & tmp) == tmp )
+ {
+ activeirqstatus = SET;
+ }
+ else
+ {
+ activeirqstatus = RESET;
+ }
+ return activeirqstatus;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetCPUID
+* Description : Returns the ID number, the version number and the implementation
+* details of the Cortex-M3 core.
+* Input : None
+* Output : None
+* Return : CPU ID.
+*******************************************************************************/
+u32 NVIC_GetCPUID(void)
+{
+ return (SCB->CPUID);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SetVectorTable
+* Description : Sets the vector table location and Offset.
+* Input : - NVIC_VectTab: specifies if the vector table is in RAM or
+* FLASH memory.
+* This parameter can be one of the following values:
+* - NVIC_VectTab_RAM
+* - NVIC_VectTab_FLASH
+* - Offset: Vector Table base offset field.
+* This value must be a multiple of 0x100.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SetVectorTable(u32 NVIC_VectTab, u32 Offset)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_VECTTAB(NVIC_VectTab));
+ assert_param(IS_NVIC_OFFSET(Offset));
+
+ SCB->VTOR = NVIC_VectTab | (Offset & (u32)0x1FFFFF80);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GenerateSystemReset
+* Description : Generates a system reset.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_GenerateSystemReset(void)
+{
+ SCB->AIRCR = AIRCR_VECTKEY_MASK | (u32)0x04;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GenerateCoreReset
+* Description : Generates a Core (Core + NVIC) reset.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_GenerateCoreReset(void)
+{
+ SCB->AIRCR = AIRCR_VECTKEY_MASK | (u32)0x01;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SystemLPConfig
+* Description : Selects the condition for the system to enter low power mode.
+* Input : - LowPowerMode: Specifies the new mode for the system to enter
+* low power mode.
+* This parameter can be one of the following values:
+* - NVIC_LP_SEVONPEND
+* - NVIC_LP_SLEEPDEEP
+* - NVIC_LP_SLEEPONEXIT
+* - NewState: new state of LP condition.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SystemLPConfig(u8 LowPowerMode, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_LP(LowPowerMode));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ SCB->SCR |= LowPowerMode;
+ }
+ else
+ {
+ SCB->SCR &= (u32)(~(u32)LowPowerMode);
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SystemHandlerConfig
+* Description : Enables or disables the specified System Handlers.
+* Input : - SystemHandler: specifies the system handler to be enabled
+* or disabled.
+* This parameter can be one of the following values:
+* - SystemHandler_MemoryManage
+* - SystemHandler_BusFault
+* - SystemHandler_UsageFault
+* - NewState: new state of specified System Handlers.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SystemHandlerConfig(u32 SystemHandler, FunctionalState NewState)
+{
+ u32 tmpreg = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_CONFIG_SYSTEM_HANDLER(SystemHandler));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ tmpreg = (u32)0x01 << (SystemHandler & (u32)0x1F);
+
+ if (NewState != DISABLE)
+ {
+ SCB->SHCSR |= tmpreg;
+ }
+ else
+ {
+ SCB->SHCSR &= ~tmpreg;
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SystemHandlerPriorityConfig
+* Description : Configures the specified System Handlers priority.
+* Input : - SystemHandler: specifies the system handler to be
+* enabled or disabled.
+* This parameter can be one of the following values:
+* - SystemHandler_MemoryManage
+* - SystemHandler_BusFault
+* - SystemHandler_UsageFault
+* - SystemHandler_SVCall
+* - SystemHandler_DebugMonitor
+* - SystemHandler_PSV
+* - SystemHandler_SysTick
+* - SystemHandlerPreemptionPriority: new priority group of the
+* specified system handlers.
+* - SystemHandlerSubPriority: new sub priority of the specified
+* system handlers.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SystemHandlerPriorityConfig(u32 SystemHandler, u8 SystemHandlerPreemptionPriority,
+ u8 SystemHandlerSubPriority)
+{
+ u32 tmp1 = 0x00, tmp2 = 0xFF, handlermask = 0x00;
+ u32 tmppriority = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_PRIORITY_SYSTEM_HANDLER(SystemHandler));
+ assert_param(IS_NVIC_PREEMPTION_PRIORITY(SystemHandlerPreemptionPriority));
+ assert_param(IS_NVIC_SUB_PRIORITY(SystemHandlerSubPriority));
+
+ tmppriority = (0x700 - (SCB->AIRCR & (u32)0x700))>> 0x08;
+ tmp1 = (0x4 - tmppriority);
+ tmp2 = tmp2 >> tmppriority;
+
+ tmppriority = (u32)SystemHandlerPreemptionPriority << tmp1;
+ tmppriority |= SystemHandlerSubPriority & tmp2;
+
+ tmppriority = tmppriority << 0x04;
+ tmp1 = SystemHandler & (u32)0xC0;
+ tmp1 = tmp1 >> 0x06;
+ tmp2 = (SystemHandler >> 0x08) & (u32)0x03;
+ tmppriority = tmppriority << (tmp2 * 0x08);
+ handlermask = (u32)0xFF << (tmp2 * 0x08);
+
+ SCB->SHPR[tmp1] &= ~handlermask;
+ SCB->SHPR[tmp1] |= tmppriority;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetSystemHandlerPendingBitStatus
+* Description : Checks whether the specified System handlers pending bit is
+* set or not.
+* Input : - SystemHandler: specifies the system handler pending bit to
+* check.
+* This parameter can be one of the following values:
+* - SystemHandler_MemoryManage
+* - SystemHandler_BusFault
+* - SystemHandler_SVCall
+* Output : None
+* Return : The new state of System Handler pending bit(SET or RESET).
+*******************************************************************************/
+ITStatus NVIC_GetSystemHandlerPendingBitStatus(u32 SystemHandler)
+{
+ ITStatus bitstatus = RESET;
+ u32 tmp = 0x00, tmppos = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GET_PENDING_SYSTEM_HANDLER(SystemHandler));
+
+ tmppos = (SystemHandler >> 0x0A);
+ tmppos &= (u32)0x0F;
+
+ tmppos = (u32)0x01 << tmppos;
+
+ tmp = SCB->SHCSR & tmppos;
+
+ if (tmp == tmppos)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SetSystemHandlerPendingBit
+* Description : Sets System Handler pending bit.
+* Input : - SystemHandler: specifies the system handler pending bit
+* to be set.
+* This parameter can be one of the following values:
+* - SystemHandler_NMI
+* - SystemHandler_PSV
+* - SystemHandler_SysTick
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SetSystemHandlerPendingBit(u32 SystemHandler)
+{
+ u32 tmp = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_SET_PENDING_SYSTEM_HANDLER(SystemHandler));
+
+ /* Get the System Handler pending bit position */
+ tmp = SystemHandler & (u32)0x1F;
+ /* Set the corresponding System Handler pending bit */
+ SCB->ICSR |= ((u32)0x01 << tmp);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_ClearSystemHandlerPendingBit
+* Description : Clears System Handler pending bit.
+* Input : - SystemHandler: specifies the system handler pending bit to
+* be clear.
+* This parameter can be one of the following values:
+* - SystemHandler_PSV
+* - SystemHandler_SysTick
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_ClearSystemHandlerPendingBit(u32 SystemHandler)
+{
+ u32 tmp = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_CLEAR_SYSTEM_HANDLER(SystemHandler));
+
+ /* Get the System Handler pending bit position */
+ tmp = SystemHandler & (u32)0x1F;
+ /* Clear the corresponding System Handler pending bit */
+ SCB->ICSR |= ((u32)0x01 << (tmp - 0x01));
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetSystemHandlerActiveBitStatus
+* Description : Checks whether the specified System handlers active bit is
+* set or not.
+* Input : - SystemHandler: specifies the system handler active bit to
+* check.
+* This parameter can be one of the following values:
+* - SystemHandler_MemoryManage
+* - SystemHandler_BusFault
+* - SystemHandler_UsageFault
+* - SystemHandler_SVCall
+* - SystemHandler_DebugMonitor
+* - SystemHandler_PSV
+* - SystemHandler_SysTick
+* Output : None
+* Return : The new state of System Handler active bit(SET or RESET).
+*******************************************************************************/
+ITStatus NVIC_GetSystemHandlerActiveBitStatus(u32 SystemHandler)
+{
+ ITStatus bitstatus = RESET;
+
+ u32 tmp = 0x00, tmppos = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GET_ACTIVE_SYSTEM_HANDLER(SystemHandler));
+
+ tmppos = (SystemHandler >> 0x0E) & (u32)0x0F;
+
+ tmppos = (u32)0x01 << tmppos;
+
+ tmp = SCB->SHCSR & tmppos;
+
+ if (tmp == tmppos)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetFaultHandlerSources
+* Description : Returns the system fault handlers sources.
+* Input : - SystemHandler: specifies the system handler to get its fault
+* sources.
+* This parameter can be one of the following values:
+* - SystemHandler_HardFault
+* - SystemHandler_MemoryManage
+* - SystemHandler_BusFault
+* - SystemHandler_UsageFault
+* - SystemHandler_DebugMonitor
+* Output : None
+* Return : Source of the fault handler.
+*******************************************************************************/
+u32 NVIC_GetFaultHandlerSources(u32 SystemHandler)
+{
+ u32 faultsources = 0x00;
+ u32 tmpreg = 0x00, tmppos = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_FAULT_SOURCE_SYSTEM_HANDLER(SystemHandler));
+
+ tmpreg = (SystemHandler >> 0x12) & (u32)0x03;
+ tmppos = (SystemHandler >> 0x14) & (u32)0x03;
+
+ if (tmpreg == 0x00)
+ {
+ faultsources = SCB->HFSR;
+ }
+ else if (tmpreg == 0x01)
+ {
+ faultsources = SCB->CFSR >> (tmppos * 0x08);
+ if (tmppos != 0x02)
+ {
+ faultsources &= (u32)0x0F;
+ }
+ else
+ {
+ faultsources &= (u32)0xFF;
+ }
+ }
+ else
+ {
+ faultsources = SCB->DFSR;
+ }
+ return faultsources;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetFaultAddress
+* Description : Returns the address of the location that generated a fault
+* handler.
+* Input : - SystemHandler: specifies the system handler to get its
+* fault address.
+* This parameter can be one of the following values:
+* - SystemHandler_MemoryManage
+* - SystemHandler_BusFault
+* Output : None
+* Return : Fault address.
+*******************************************************************************/
+u32 NVIC_GetFaultAddress(u32 SystemHandler)
+{
+ u32 faultaddress = 0x00;
+ u32 tmp = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_FAULT_ADDRESS_SYSTEM_HANDLER(SystemHandler));
+
+ tmp = (SystemHandler >> 0x16) & (u32)0x01;
+
+ if (tmp == 0x00)
+ {
+ faultaddress = SCB->MMFAR;
+ }
+ else
+ {
+ faultaddress = SCB->BFAR;
+ }
+ return faultaddress;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_pwr.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_pwr.c new file mode 100755 index 0000000..fb8fca2 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_pwr.c @@ -0,0 +1,280 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_pwr.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the PWR firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_pwr.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* --------- PWR registers bit address in the alias region ---------- */
+#define PWR_OFFSET (PWR_BASE - PERIPH_BASE)
+
+/* --- CR Register ---*/
+/* Alias word address of DBP bit */
+#define CR_OFFSET (PWR_OFFSET + 0x00)
+#define DBP_BitNumber 0x08
+#define CR_DBP_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4))
+
+/* Alias word address of PVDE bit */
+#define PVDE_BitNumber 0x04
+#define CR_PVDE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4))
+
+/* --- CSR Register ---*/
+/* Alias word address of EWUP bit */
+#define CSR_OFFSET (PWR_OFFSET + 0x04)
+#define EWUP_BitNumber 0x08
+#define CSR_EWUP_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4))
+
+/* ------------------ PWR registers bit mask ------------------------ */
+/* CR register bit mask */
+#define CR_PDDS_Set ((u32)0x00000002)
+#define CR_DS_Mask ((u32)0xFFFFFFFC)
+#define CR_CWUF_Set ((u32)0x00000004)
+#define CR_PLS_Mask ((u32)0xFFFFFF1F)
+
+/* --------- Cortex System Control register bit mask ---------------- */
+/* Cortex System Control register address */
+#define SCB_SysCtrl ((u32)0xE000ED10)
+/* SLEEPDEEP bit mask */
+#define SysCtrl_SLEEPDEEP_Set ((u32)0x00000004)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : PWR_DeInit
+* Description : Deinitializes the PWR peripheral registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_DeInit(void)
+{
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, DISABLE);
+}
+
+/*******************************************************************************
+* Function Name : PWR_BackupAccessCmd
+* Description : Enables or disables access to the RTC and backup registers.
+* Input : - NewState: new state of the access to the RTC and backup
+* registers. This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_BackupAccessCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CR_DBP_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : PWR_PVDCmd
+* Description : Enables or disables the Power Voltage Detector(PVD).
+* Input : - NewState: new state of the PVD.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_PVDCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CR_PVDE_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : PWR_PVDLevelConfig
+* Description : Configures the voltage threshold detected by the Power Voltage
+* Detector(PVD).
+* Input : - PWR_PVDLevel: specifies the PVD detection level
+* This parameter can be one of the following values:
+* - PWR_PVDLevel_2V2: PVD detection level set to 2.2V
+* - PWR_PVDLevel_2V3: PVD detection level set to 2.3V
+* - PWR_PVDLevel_2V4: PVD detection level set to 2.4V
+* - PWR_PVDLevel_2V5: PVD detection level set to 2.5V
+* - PWR_PVDLevel_2V6: PVD detection level set to 2.6V
+* - PWR_PVDLevel_2V7: PVD detection level set to 2.7V
+* - PWR_PVDLevel_2V8: PVD detection level set to 2.8V
+* - PWR_PVDLevel_2V9: PVD detection level set to 2.9V
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_PVDLevelConfig(u32 PWR_PVDLevel)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel));
+
+ tmpreg = PWR->CR;
+
+ /* Clear PLS[7:5] bits */
+ tmpreg &= CR_PLS_Mask;
+
+ /* Set PLS[7:5] bits according to PWR_PVDLevel value */
+ tmpreg |= PWR_PVDLevel;
+
+ /* Store the new value */
+ PWR->CR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : PWR_WakeUpPinCmd
+* Description : Enables or disables the WakeUp Pin functionality.
+* Input : - NewState: new state of the WakeUp Pin functionality.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_WakeUpPinCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CSR_EWUP_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : PWR_EnterSTOPMode
+* Description : Enters STOP mode.
+* Input : - PWR_Regulator: specifies the regulator state in STOP mode.
+* This parameter can be one of the following values:
+* - PWR_Regulator_ON: STOP mode with regulator ON
+* - PWR_Regulator_LowPower: STOP mode with
+* regulator in low power mode
+* - PWR_STOPEntry: specifies if STOP mode in entered with WFI or
+* WFE instruction.
+* This parameter can be one of the following values:
+* - PWR_STOPEntry_WFI: enter STOP mode with WFI instruction
+* - PWR_STOPEntry_WFE: enter STOP mode with WFE instruction
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_EnterSTOPMode(u32 PWR_Regulator, u8 PWR_STOPEntry)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_PWR_REGULATOR(PWR_Regulator));
+ assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry));
+
+ /* Select the regulator state in STOP mode ---------------------------------*/
+ tmpreg = PWR->CR;
+
+ /* Clear PDDS and LPDS bits */
+ tmpreg &= CR_DS_Mask;
+
+ /* Set LPDS bit according to PWR_Regulator value */
+ tmpreg |= PWR_Regulator;
+
+ /* Store the new value */
+ PWR->CR = tmpreg;
+
+ /* Set SLEEPDEEP bit of Cortex System Control Register */
+ *(vu32 *) SCB_SysCtrl |= SysCtrl_SLEEPDEEP_Set;
+
+ /* Select STOP mode entry --------------------------------------------------*/
+ if(PWR_STOPEntry == PWR_STOPEntry_WFI)
+ {
+ /* Request Wait For Interrupt */
+ __WFI();
+ }
+ else
+ {
+ /* Request Wait For Event */
+ __WFE();
+ }
+}
+
+/*******************************************************************************
+* Function Name : PWR_EnterSTANDBYMode
+* Description : Enters STANDBY mode.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_EnterSTANDBYMode(void)
+{
+ /* Clear Wake-up flag */
+ PWR->CR |= CR_CWUF_Set;
+
+ /* Select STANDBY mode */
+ PWR->CR |= CR_PDDS_Set;
+
+ /* Set SLEEPDEEP bit of Cortex System Control Register */
+ *(vu32 *) SCB_SysCtrl |= SysCtrl_SLEEPDEEP_Set;
+
+ /* Request Wait For Interrupt */
+ __WFI();
+}
+
+/*******************************************************************************
+* Function Name : PWR_GetFlagStatus
+* Description : Checks whether the specified PWR flag is set or not.
+* Input : - PWR_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - PWR_FLAG_WU: Wake Up flag
+* - PWR_FLAG_SB: StandBy flag
+* - PWR_FLAG_PVDO: PVD Output
+* Output : None
+* Return : The new state of PWR_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus PWR_GetFlagStatus(u32 PWR_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_PWR_GET_FLAG(PWR_FLAG));
+
+ if ((PWR->CSR & PWR_FLAG) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+
+ /* Return the flag status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : PWR_ClearFlag
+* Description : Clears the PWR's pending flags.
+* Input : - PWR_FLAG: specifies the flag to clear.
+* This parameter can be one of the following values:
+* - PWR_FLAG_WU: Wake Up flag
+* - PWR_FLAG_SB: StandBy flag
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_ClearFlag(u32 PWR_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG));
+
+ PWR->CR |= PWR_FLAG << 2;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_rcc.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_rcc.c new file mode 100755 index 0000000..4d774da --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_rcc.c @@ -0,0 +1,1104 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_rcc.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the RCC firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ------------ RCC registers bit address in the alias region ----------- */
+#define RCC_OFFSET (RCC_BASE - PERIPH_BASE)
+
+/* --- CR Register ---*/
+/* Alias word address of HSION bit */
+#define CR_OFFSET (RCC_OFFSET + 0x00)
+#define HSION_BitNumber 0x00
+#define CR_HSION_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4))
+
+/* Alias word address of PLLON bit */
+#define PLLON_BitNumber 0x18
+#define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4))
+
+/* Alias word address of CSSON bit */
+#define CSSON_BitNumber 0x13
+#define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4))
+
+/* --- CFGR Register ---*/
+/* Alias word address of USBPRE bit */
+#define CFGR_OFFSET (RCC_OFFSET + 0x04)
+#define USBPRE_BitNumber 0x16
+#define CFGR_USBPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4))
+
+/* --- BDCR Register ---*/
+/* Alias word address of RTCEN bit */
+#define BDCR_OFFSET (RCC_OFFSET + 0x20)
+#define RTCEN_BitNumber 0x0F
+#define BDCR_RTCEN_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4))
+
+/* Alias word address of BDRST bit */
+#define BDRST_BitNumber 0x10
+#define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4))
+
+/* --- CSR Register ---*/
+/* Alias word address of LSION bit */
+#define CSR_OFFSET (RCC_OFFSET + 0x24)
+#define LSION_BitNumber 0x00
+#define CSR_LSION_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4))
+
+/* ---------------------- RCC registers bit mask ------------------------ */
+/* CR register bit mask */
+#define CR_HSEBYP_Reset ((u32)0xFFFBFFFF)
+#define CR_HSEBYP_Set ((u32)0x00040000)
+#define CR_HSEON_Reset ((u32)0xFFFEFFFF)
+#define CR_HSEON_Set ((u32)0x00010000)
+#define CR_HSITRIM_Mask ((u32)0xFFFFFF07)
+
+/* CFGR register bit mask */
+#define CFGR_PLL_Mask ((u32)0xFFC0FFFF)
+#define CFGR_PLLMull_Mask ((u32)0x003C0000)
+#define CFGR_PLLSRC_Mask ((u32)0x00010000)
+#define CFGR_PLLXTPRE_Mask ((u32)0x00020000)
+#define CFGR_SWS_Mask ((u32)0x0000000C)
+#define CFGR_SW_Mask ((u32)0xFFFFFFFC)
+#define CFGR_HPRE_Reset_Mask ((u32)0xFFFFFF0F)
+#define CFGR_HPRE_Set_Mask ((u32)0x000000F0)
+#define CFGR_PPRE1_Reset_Mask ((u32)0xFFFFF8FF)
+#define CFGR_PPRE1_Set_Mask ((u32)0x00000700)
+#define CFGR_PPRE2_Reset_Mask ((u32)0xFFFFC7FF)
+#define CFGR_PPRE2_Set_Mask ((u32)0x00003800)
+#define CFGR_ADCPRE_Reset_Mask ((u32)0xFFFF3FFF)
+#define CFGR_ADCPRE_Set_Mask ((u32)0x0000C000)
+
+/* CSR register bit mask */
+#define CSR_RMVF_Set ((u32)0x01000000)
+
+/* RCC Flag Mask */
+#define FLAG_Mask ((u8)0x1F)
+
+/* Typical Value of the HSI in Hz */
+#define HSI_Value ((u32)8000000)
+
+/* CIR register byte 2 (Bits[15:8]) base address */
+#define CIR_BYTE2_ADDRESS ((u32)0x40021009)
+/* CIR register byte 3 (Bits[23:16]) base address */
+#define CIR_BYTE3_ADDRESS ((u32)0x4002100A)
+
+/* CFGR register byte 4 (Bits[31:24]) base address */
+#define CFGR_BYTE4_ADDRESS ((u32)0x40021007)
+
+/* BDCR register base address */
+#define BDCR_ADDRESS (PERIPH_BASE + BDCR_OFFSET)
+
+/* Time out for HSE start up */
+#define HSEStartUp_TimeOut ((u16)0x01FF)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+static uc8 APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
+static uc8 ADCPrescTable[4] = {2, 4, 6, 8};
+
+static volatile FlagStatus HSEStatus;
+static vu32 StartUpCounter = 0;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : RCC_DeInit
+* Description : Resets the RCC clock configuration to the default reset state.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_DeInit(void)
+{
+ /* Set HSION bit */
+ RCC->CR |= (u32)0x00000001;
+
+ /* Reset SW[1:0], HPRE[3:0], PPRE1[2:0], PPRE2[2:0], ADCPRE[1:0] and MCO[2:0] bits */
+ RCC->CFGR &= (u32)0xF8FF0000;
+
+ /* Reset HSEON, CSSON and PLLON bits */
+ RCC->CR &= (u32)0xFEF6FFFF;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= (u32)0xFFFBFFFF;
+
+ /* Reset PLLSRC, PLLXTPRE, PLLMUL[3:0] and USBPRE bits */
+ RCC->CFGR &= (u32)0xFF80FFFF;
+
+ /* Disable all interrupts */
+ RCC->CIR = 0x00000000;
+}
+
+/*******************************************************************************
+* Function Name : RCC_HSEConfig
+* Description : Configures the External High Speed oscillator (HSE).
+* HSE can not be stopped if it is used directly or through the
+* PLL as system clock.
+* Input : - RCC_HSE: specifies the new state of the HSE.
+* This parameter can be one of the following values:
+* - RCC_HSE_OFF: HSE oscillator OFF
+* - RCC_HSE_ON: HSE oscillator ON
+* - RCC_HSE_Bypass: HSE oscillator bypassed with external
+* clock
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_HSEConfig(u32 RCC_HSE)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_HSE(RCC_HSE));
+
+ /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/
+ /* Reset HSEON bit */
+ RCC->CR &= CR_HSEON_Reset;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= CR_HSEBYP_Reset;
+
+ /* Configure HSE (RCC_HSE_OFF is already covered by the code section above) */
+ switch(RCC_HSE)
+ {
+ case RCC_HSE_ON:
+ /* Set HSEON bit */
+ RCC->CR |= CR_HSEON_Set;
+ break;
+
+ case RCC_HSE_Bypass:
+ /* Set HSEBYP and HSEON bits */
+ RCC->CR |= CR_HSEBYP_Set | CR_HSEON_Set;
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_WaitForHSEStartUp
+* Description : Waits for HSE start-up.
+* Input : None
+* Output : None
+* Return : An ErrorStatus enumuration value:
+* - SUCCESS: HSE oscillator is stable and ready to use
+* - ERROR: HSE oscillator not yet ready
+*******************************************************************************/
+ErrorStatus RCC_WaitForHSEStartUp(void)
+{
+ ErrorStatus status = ERROR;
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY);
+ StartUpCounter++;
+ } while((HSEStatus == RESET) && (StartUpCounter != HSEStartUp_TimeOut));
+
+
+ if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET)
+ {
+ status = SUCCESS;
+ }
+ else
+ {
+ status = ERROR;
+ }
+
+ return (status);
+}
+
+/*******************************************************************************
+* Function Name : RCC_AdjustHSICalibrationValue
+* Description : Adjusts the Internal High Speed oscillator (HSI) calibration
+* value.
+* Input : - HSICalibrationValue: specifies the calibration trimming value.
+* This parameter must be a number between 0 and 0x1F.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_AdjustHSICalibrationValue(u8 HSICalibrationValue)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_CALIBRATION_VALUE(HSICalibrationValue));
+
+ tmpreg = RCC->CR;
+
+ /* Clear HSITRIM[4:0] bits */
+ tmpreg &= CR_HSITRIM_Mask;
+
+ /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */
+ tmpreg |= (u32)HSICalibrationValue << 3;
+
+ /* Store the new value */
+ RCC->CR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : RCC_HSICmd
+* Description : Enables or disables the Internal High Speed oscillator (HSI).
+* HSI can not be stopped if it is used directly or through the
+* PLL as system clock.
+* Input : - NewState: new state of the HSI.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_HSICmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CR_HSION_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : RCC_PLLConfig
+* Description : Configures the PLL clock source and multiplication factor.
+* This function must be used only when the PLL is disabled.
+* Input : - RCC_PLLSource: specifies the PLL entry clock source.
+* This parameter can be one of the following values:
+* - RCC_PLLSource_HSI_Div2: HSI oscillator clock divided
+* by 2 selected as PLL clock entry
+* - RCC_PLLSource_HSE_Div1: HSE oscillator clock selected
+* as PLL clock entry
+* - RCC_PLLSource_HSE_Div2: HSE oscillator clock divided
+* by 2 selected as PLL clock entry
+* - RCC_PLLMul: specifies the PLL multiplication factor.
+* This parameter can be RCC_PLLMul_x where x:[2,16]
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_PLLConfig(u32 RCC_PLLSource, u32 RCC_PLLMul)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource));
+ assert_param(IS_RCC_PLL_MUL(RCC_PLLMul));
+
+ tmpreg = RCC->CFGR;
+
+ /* Clear PLLSRC, PLLXTPRE and PLLMUL[3:0] bits */
+ tmpreg &= CFGR_PLL_Mask;
+
+ /* Set the PLL configuration bits */
+ tmpreg |= RCC_PLLSource | RCC_PLLMul;
+
+ /* Store the new value */
+ RCC->CFGR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : RCC_PLLCmd
+* Description : Enables or disables the PLL.
+* The PLL can not be disabled if it is used as system clock.
+* Input : - NewState: new state of the PLL.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_PLLCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CR_PLLON_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : RCC_SYSCLKConfig
+* Description : Configures the system clock (SYSCLK).
+* Input : - RCC_SYSCLKSource: specifies the clock source used as system
+* clock. This parameter can be one of the following values:
+* - RCC_SYSCLKSource_HSI: HSI selected as system clock
+* - RCC_SYSCLKSource_HSE: HSE selected as system clock
+* - RCC_SYSCLKSource_PLLCLK: PLL selected as system clock
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_SYSCLKConfig(u32 RCC_SYSCLKSource)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource));
+
+ tmpreg = RCC->CFGR;
+
+ /* Clear SW[1:0] bits */
+ tmpreg &= CFGR_SW_Mask;
+
+ /* Set SW[1:0] bits according to RCC_SYSCLKSource value */
+ tmpreg |= RCC_SYSCLKSource;
+
+ /* Store the new value */
+ RCC->CFGR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : RCC_GetSYSCLKSource
+* Description : Returns the clock source used as system clock.
+* Input : None
+* Output : None
+* Return : The clock source used as system clock. The returned value can
+* be one of the following:
+* - 0x00: HSI used as system clock
+* - 0x04: HSE used as system clock
+* - 0x08: PLL used as system clock
+*******************************************************************************/
+u8 RCC_GetSYSCLKSource(void)
+{
+ return ((u8)(RCC->CFGR & CFGR_SWS_Mask));
+}
+
+/*******************************************************************************
+* Function Name : RCC_HCLKConfig
+* Description : Configures the AHB clock (HCLK).
+* Input : - RCC_SYSCLK: defines the AHB clock divider. This clock is
+* derived from the system clock (SYSCLK).
+* This parameter can be one of the following values:
+* - RCC_SYSCLK_Div1: AHB clock = SYSCLK
+* - RCC_SYSCLK_Div2: AHB clock = SYSCLK/2
+* - RCC_SYSCLK_Div4: AHB clock = SYSCLK/4
+* - RCC_SYSCLK_Div8: AHB clock = SYSCLK/8
+* - RCC_SYSCLK_Div16: AHB clock = SYSCLK/16
+* - RCC_SYSCLK_Div64: AHB clock = SYSCLK/64
+* - RCC_SYSCLK_Div128: AHB clock = SYSCLK/128
+* - RCC_SYSCLK_Div256: AHB clock = SYSCLK/256
+* - RCC_SYSCLK_Div512: AHB clock = SYSCLK/512
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_HCLKConfig(u32 RCC_SYSCLK)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_HCLK(RCC_SYSCLK));
+
+ tmpreg = RCC->CFGR;
+
+ /* Clear HPRE[3:0] bits */
+ tmpreg &= CFGR_HPRE_Reset_Mask;
+
+ /* Set HPRE[3:0] bits according to RCC_SYSCLK value */
+ tmpreg |= RCC_SYSCLK;
+
+ /* Store the new value */
+ RCC->CFGR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : RCC_PCLK1Config
+* Description : Configures the Low Speed APB clock (PCLK1).
+* Input : - RCC_HCLK: defines the APB1 clock divider. This clock is
+* derived from the AHB clock (HCLK).
+* This parameter can be one of the following values:
+* - RCC_HCLK_Div1: APB1 clock = HCLK
+* - RCC_HCLK_Div2: APB1 clock = HCLK/2
+* - RCC_HCLK_Div4: APB1 clock = HCLK/4
+* - RCC_HCLK_Div8: APB1 clock = HCLK/8
+* - RCC_HCLK_Div16: APB1 clock = HCLK/16
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_PCLK1Config(u32 RCC_HCLK)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_PCLK(RCC_HCLK));
+
+ tmpreg = RCC->CFGR;
+
+ /* Clear PPRE1[2:0] bits */
+ tmpreg &= CFGR_PPRE1_Reset_Mask;
+
+ /* Set PPRE1[2:0] bits according to RCC_HCLK value */
+ tmpreg |= RCC_HCLK;
+
+ /* Store the new value */
+ RCC->CFGR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : RCC_PCLK2Config
+* Description : Configures the High Speed APB clock (PCLK2).
+* Input : - RCC_HCLK: defines the APB2 clock divider. This clock is
+* derived from the AHB clock (HCLK).
+* This parameter can be one of the following values:
+* - RCC_HCLK_Div1: APB2 clock = HCLK
+* - RCC_HCLK_Div2: APB2 clock = HCLK/2
+* - RCC_HCLK_Div4: APB2 clock = HCLK/4
+* - RCC_HCLK_Div8: APB2 clock = HCLK/8
+* - RCC_HCLK_Div16: APB2 clock = HCLK/16
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_PCLK2Config(u32 RCC_HCLK)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_PCLK(RCC_HCLK));
+
+ tmpreg = RCC->CFGR;
+
+ /* Clear PPRE2[2:0] bits */
+ tmpreg &= CFGR_PPRE2_Reset_Mask;
+
+ /* Set PPRE2[2:0] bits according to RCC_HCLK value */
+ tmpreg |= RCC_HCLK << 3;
+
+ /* Store the new value */
+ RCC->CFGR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : RCC_ITConfig
+* Description : Enables or disables the specified RCC interrupts.
+* Input : - RCC_IT: specifies the RCC interrupt sources to be enabled
+* or disabled.
+* This parameter can be any combination of the following values:
+* - RCC_IT_LSIRDY: LSI ready interrupt
+* - RCC_IT_LSERDY: LSE ready interrupt
+* - RCC_IT_HSIRDY: HSI ready interrupt
+* - RCC_IT_HSERDY: HSE ready interrupt
+* - RCC_IT_PLLRDY: PLL ready interrupt
+* - NewState: new state of the specified RCC interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_ITConfig(u8 RCC_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_IT(RCC_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Perform Byte access to RCC_CIR[12:8] bits to enable the selected interrupts */
+ *(vu8 *) CIR_BYTE2_ADDRESS |= RCC_IT;
+ }
+ else
+ {
+ /* Perform Byte access to RCC_CIR[12:8] bits to disable the selected interrupts */
+ *(vu8 *) CIR_BYTE2_ADDRESS &= (u8)~RCC_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_USBCLKConfig
+* Description : Configures the USB clock (USBCLK).
+* Input : - RCC_USBCLKSource: specifies the USB clock source. This clock
+* is derived from the PLL output.
+* This parameter can be one of the following values:
+* - RCC_USBCLKSource_PLLCLK_1Div5: PLL clock divided by 1,5
+* selected as USB clock source
+* - RCC_USBCLKSource_PLLCLK_Div1: PLL clock selected as USB
+* clock source
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_USBCLKConfig(u32 RCC_USBCLKSource)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_USBCLK_SOURCE(RCC_USBCLKSource));
+
+ *(vu32 *) CFGR_USBPRE_BB = RCC_USBCLKSource;
+}
+
+/*******************************************************************************
+* Function Name : RCC_ADCCLKConfig
+* Description : Configures the ADC clock (ADCCLK).
+* Input : - RCC_PCLK2: defines the ADC clock divider. This clock is
+* derived from the APB2 clock (PCLK2).
+* This parameter can be one of the following values:
+* - RCC_PCLK2_Div2: ADC clock = PCLK2/2
+* - RCC_PCLK2_Div4: ADC clock = PCLK2/4
+* - RCC_PCLK2_Div6: ADC clock = PCLK2/6
+* - RCC_PCLK2_Div8: ADC clock = PCLK2/8
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_ADCCLKConfig(u32 RCC_PCLK2)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_ADCCLK(RCC_PCLK2));
+
+ tmpreg = RCC->CFGR;
+
+ /* Clear ADCPRE[1:0] bits */
+ tmpreg &= CFGR_ADCPRE_Reset_Mask;
+
+ /* Set ADCPRE[1:0] bits according to RCC_PCLK2 value */
+ tmpreg |= RCC_PCLK2;
+
+ /* Store the new value */
+ RCC->CFGR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : RCC_LSEConfig
+* Description : Configures the External Low Speed oscillator (LSE).
+* Input : - RCC_LSE: specifies the new state of the LSE.
+* This parameter can be one of the following values:
+* - RCC_LSE_OFF: LSE oscillator OFF
+* - RCC_LSE_ON: LSE oscillator ON
+* - RCC_LSE_Bypass: LSE oscillator bypassed with external
+* clock
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_LSEConfig(u8 RCC_LSE)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_LSE(RCC_LSE));
+
+ /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/
+ /* Reset LSEON bit */
+ *(vu8 *) BDCR_ADDRESS = RCC_LSE_OFF;
+
+ /* Reset LSEBYP bit */
+ *(vu8 *) BDCR_ADDRESS = RCC_LSE_OFF;
+
+ /* Configure LSE (RCC_LSE_OFF is already covered by the code section above) */
+ switch(RCC_LSE)
+ {
+ case RCC_LSE_ON:
+ /* Set LSEON bit */
+ *(vu8 *) BDCR_ADDRESS = RCC_LSE_ON;
+ break;
+
+ case RCC_LSE_Bypass:
+ /* Set LSEBYP and LSEON bits */
+ *(vu8 *) BDCR_ADDRESS = RCC_LSE_Bypass | RCC_LSE_ON;
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_LSICmd
+* Description : Enables or disables the Internal Low Speed oscillator (LSI).
+* LSI can not be disabled if the IWDG is running.
+* Input : - NewState: new state of the LSI.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_LSICmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CSR_LSION_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : RCC_RTCCLKConfig
+* Description : Configures the RTC clock (RTCCLK).
+* Once the RTC clock is selected it can’t be changed unless the
+* Backup domain is reset.
+* Input : - RCC_RTCCLKSource: specifies the RTC clock source.
+* This parameter can be one of the following values:
+* - RCC_RTCCLKSource_LSE: LSE selected as RTC clock
+* - RCC_RTCCLKSource_LSI: LSI selected as RTC clock
+* - RCC_RTCCLKSource_HSE_Div128: HSE clock divided by 128
+* selected as RTC clock
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_RTCCLKConfig(u32 RCC_RTCCLKSource)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource));
+
+ /* Select the RTC clock source */
+ RCC->BDCR |= RCC_RTCCLKSource;
+}
+
+/*******************************************************************************
+* Function Name : RCC_RTCCLKCmd
+* Description : Enables or disables the RTC clock.
+* This function must be used only after the RTC clock was
+* selected using the RCC_RTCCLKConfig function.
+* Input : - NewState: new state of the RTC clock.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_RTCCLKCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) BDCR_RTCEN_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : RCC_GetClocksFreq
+* Description : Returns the frequencies of different on chip clocks.
+* Input : - RCC_Clocks: pointer to a RCC_ClocksTypeDef structure which
+* will hold the clocks frequencies.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)
+{
+ u32 tmp = 0, pllmull = 0, pllsource = 0, presc = 0;
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+ tmp = RCC->CFGR & CFGR_SWS_Mask;
+
+ switch (tmp)
+ {
+ case 0x00: /* HSI used as system clock */
+ RCC_Clocks->SYSCLK_Frequency = HSI_Value;
+ break;
+
+ case 0x04: /* HSE used as system clock */
+ RCC_Clocks->SYSCLK_Frequency = HSE_Value;
+ break;
+
+ case 0x08: /* PLL used as system clock */
+ /* Get PLL clock source and multiplication factor ----------------------*/
+ pllmull = RCC->CFGR & CFGR_PLLMull_Mask;
+ pllmull = ( pllmull >> 18) + 2;
+
+ pllsource = RCC->CFGR & CFGR_PLLSRC_Mask;
+
+ if (pllsource == 0x00)
+ {/* HSI oscillator clock divided by 2 selected as PLL clock entry */
+ RCC_Clocks->SYSCLK_Frequency = (HSI_Value >> 1) * pllmull;
+ }
+ else
+ {/* HSE selected as PLL clock entry */
+
+ if ((RCC->CFGR & CFGR_PLLXTPRE_Mask) != (u32)RESET)
+ {/* HSE oscillator clock divided by 2 */
+
+ RCC_Clocks->SYSCLK_Frequency = (HSE_Value >> 1) * pllmull;
+ }
+ else
+ {
+ RCC_Clocks->SYSCLK_Frequency = HSE_Value * pllmull;
+ }
+ }
+ break;
+
+ default:
+ RCC_Clocks->SYSCLK_Frequency = HSI_Value;
+ break;
+ }
+
+ /* Compute HCLK, PCLK1, PCLK2 and ADCCLK clocks frequencies ----------------*/
+ /* Get HCLK prescaler */
+ tmp = RCC->CFGR & CFGR_HPRE_Set_Mask;
+ tmp = tmp >> 4;
+ presc = APBAHBPrescTable[tmp];
+
+ /* HCLK clock frequency */
+ RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> presc;
+
+ /* Get PCLK1 prescaler */
+ tmp = RCC->CFGR & CFGR_PPRE1_Set_Mask;
+ tmp = tmp >> 8;
+ presc = APBAHBPrescTable[tmp];
+
+ /* PCLK1 clock frequency */
+ RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc;
+
+ /* Get PCLK2 prescaler */
+ tmp = RCC->CFGR & CFGR_PPRE2_Set_Mask;
+ tmp = tmp >> 11;
+ presc = APBAHBPrescTable[tmp];
+
+ /* PCLK2 clock frequency */
+ RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> presc;
+
+ /* Get ADCCLK prescaler */
+ tmp = RCC->CFGR & CFGR_ADCPRE_Set_Mask;
+ tmp = tmp >> 14;
+ presc = ADCPrescTable[tmp];
+
+ /* ADCCLK clock frequency */
+ RCC_Clocks->ADCCLK_Frequency = RCC_Clocks->PCLK2_Frequency / presc;
+}
+
+/*******************************************************************************
+* Function Name : RCC_AHBPeriphClockCmd
+* Description : Enables or disables the AHB peripheral clock.
+* Input : - RCC_AHBPeriph: specifies the AHB peripheral to gates its clock.
+* This parameter can be any combination of the following values:
+* - RCC_AHBPeriph_DMA1
+* - RCC_AHBPeriph_DMA2
+* - RCC_AHBPeriph_SRAM
+* - RCC_AHBPeriph_FLITF
+* - RCC_AHBPeriph_CRC
+* - RCC_AHBPeriph_FSMC
+* - RCC_AHBPeriph_SDIO
+* SRAM and FLITF clock can be disabled only during sleep mode.
+* - NewState: new state of the specified peripheral clock.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_AHBPeriphClockCmd(u32 RCC_AHBPeriph, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_AHB_PERIPH(RCC_AHBPeriph));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ RCC->AHBENR |= RCC_AHBPeriph;
+ }
+ else
+ {
+ RCC->AHBENR &= ~RCC_AHBPeriph;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_APB2PeriphClockCmd
+* Description : Enables or disables the High Speed APB (APB2) peripheral clock.
+* Input : - RCC_APB2Periph: specifies the APB2 peripheral to gates its
+* clock.
+* This parameter can be any combination of the following values:
+* - RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB,
+* RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE,
+* RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1,
+* RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1,
+* RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3,
+* RCC_APB2Periph_ALL
+* - NewState: new state of the specified peripheral clock.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_APB2PeriphClockCmd(u32 RCC_APB2Periph, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ RCC->APB2ENR |= RCC_APB2Periph;
+ }
+ else
+ {
+ RCC->APB2ENR &= ~RCC_APB2Periph;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_APB1PeriphClockCmd
+* Description : Enables or disables the Low Speed APB (APB1) peripheral clock.
+* Input : - RCC_APB1Periph: specifies the APB1 peripheral to gates its
+* clock.
+* This parameter can be any combination of the following values:
+* - RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4,
+* RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7,
+* RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3,
+* RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4,
+* RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2,
+* RCC_APB1Periph_USB, RCC_APB1Periph_CAN, RCC_APB1Periph_BKP,
+* RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_ALL
+* - NewState: new state of the specified peripheral clock.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_APB1PeriphClockCmd(u32 RCC_APB1Periph, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ RCC->APB1ENR |= RCC_APB1Periph;
+ }
+ else
+ {
+ RCC->APB1ENR &= ~RCC_APB1Periph;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_APB2PeriphResetCmd
+* Description : Forces or releases High Speed APB (APB2) peripheral reset.
+* Input : - RCC_APB2Periph: specifies the APB2 peripheral to reset.
+* This parameter can be any combination of the following values:
+* - RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB,
+* RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE,
+* RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1,
+* RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1,
+* RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3,
+* RCC_APB2Periph_ALL
+* - NewState: new state of the specified peripheral reset.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_APB2PeriphResetCmd(u32 RCC_APB2Periph, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ RCC->APB2RSTR |= RCC_APB2Periph;
+ }
+ else
+ {
+ RCC->APB2RSTR &= ~RCC_APB2Periph;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_APB1PeriphResetCmd
+* Description : Forces or releases Low Speed APB (APB1) peripheral reset.
+* Input : - RCC_APB1Periph: specifies the APB1 peripheral to reset.
+* This parameter can be any combination of the following values:
+* - RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4,
+* RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7,
+* RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3,
+* RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4,
+* RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2,
+* RCC_APB1Periph_USB, RCC_APB1Periph_CAN, RCC_APB1Periph_BKP,
+* RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_ALL
+* - NewState: new state of the specified peripheral clock.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_APB1PeriphResetCmd(u32 RCC_APB1Periph, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ RCC->APB1RSTR |= RCC_APB1Periph;
+ }
+ else
+ {
+ RCC->APB1RSTR &= ~RCC_APB1Periph;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_BackupResetCmd
+* Description : Forces or releases the Backup domain reset.
+* Input : - NewState: new state of the Backup domain reset.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_BackupResetCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) BDCR_BDRST_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : RCC_ClockSecuritySystemCmd
+* Description : Enables or disables the Clock Security System.
+* Input : - NewState: new state of the Clock Security System..
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_ClockSecuritySystemCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CR_CSSON_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : RCC_MCOConfig
+* Description : Selects the clock source to output on MCO pin.
+* Input : - RCC_MCO: specifies the clock source to output.
+* This parameter can be one of the following values:
+* - RCC_MCO_NoClock: No clock selected
+* - RCC_MCO_SYSCLK: System clock selected
+* - RCC_MCO_HSI: HSI oscillator clock selected
+* - RCC_MCO_HSE: HSE oscillator clock selected
+* - RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_MCOConfig(u8 RCC_MCO)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_MCO(RCC_MCO));
+
+ /* Perform Byte access to MCO[2:0] bits to select the MCO source */
+ *(vu8 *) CFGR_BYTE4_ADDRESS = RCC_MCO;
+}
+
+/*******************************************************************************
+* Function Name : RCC_GetFlagStatus
+* Description : Checks whether the specified RCC flag is set or not.
+* Input : - RCC_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - RCC_FLAG_HSIRDY: HSI oscillator clock ready
+* - RCC_FLAG_HSERDY: HSE oscillator clock ready
+* - RCC_FLAG_PLLRDY: PLL clock ready
+* - RCC_FLAG_LSERDY: LSE oscillator clock ready
+* - RCC_FLAG_LSIRDY: LSI oscillator clock ready
+* - RCC_FLAG_PINRST: Pin reset
+* - RCC_FLAG_PORRST: POR/PDR reset
+* - RCC_FLAG_SFTRST: Software reset
+* - RCC_FLAG_IWDGRST: Independent Watchdog reset
+* - RCC_FLAG_WWDGRST: Window Watchdog reset
+* - RCC_FLAG_LPWRRST: Low Power reset
+* Output : None
+* Return : The new state of RCC_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus RCC_GetFlagStatus(u8 RCC_FLAG)
+{
+ u32 tmp = 0;
+ u32 statusreg = 0;
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_FLAG(RCC_FLAG));
+
+ /* Get the RCC register index */
+ tmp = RCC_FLAG >> 5;
+
+ if (tmp == 1) /* The flag to check is in CR register */
+ {
+ statusreg = RCC->CR;
+ }
+ else if (tmp == 2) /* The flag to check is in BDCR register */
+ {
+ statusreg = RCC->BDCR;
+ }
+ else /* The flag to check is in CSR register */
+ {
+ statusreg = RCC->CSR;
+ }
+
+ /* Get the flag position */
+ tmp = RCC_FLAG & FLAG_Mask;
+
+ if ((statusreg & ((u32)1 << tmp)) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+
+ /* Return the flag status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : RCC_ClearFlag
+* Description : Clears the RCC reset flags.
+* The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST,
+* RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST,
+* RCC_FLAG_LPWRRST
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_ClearFlag(void)
+{
+ /* Set RMVF bit to clear the reset flags */
+ RCC->CSR |= CSR_RMVF_Set;
+}
+
+/*******************************************************************************
+* Function Name : RCC_GetITStatus
+* Description : Checks whether the specified RCC interrupt has occurred or not.
+* Input : - RCC_IT: specifies the RCC interrupt source to check.
+* This parameter can be one of the following values:
+* - RCC_IT_LSIRDY: LSI ready interrupt
+* - RCC_IT_LSERDY: LSE ready interrupt
+* - RCC_IT_HSIRDY: HSI ready interrupt
+* - RCC_IT_HSERDY: HSE ready interrupt
+* - RCC_IT_PLLRDY: PLL ready interrupt
+* - RCC_IT_CSS: Clock Security System interrupt
+* Output : None
+* Return : The new state of RCC_IT (SET or RESET).
+*******************************************************************************/
+ITStatus RCC_GetITStatus(u8 RCC_IT)
+{
+ ITStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_GET_IT(RCC_IT));
+
+ /* Check the status of the specified RCC interrupt */
+ if ((RCC->CIR & RCC_IT) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+
+ /* Return the RCC_IT status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : RCC_ClearITPendingBit
+* Description : Clears the RCC’s interrupt pending bits.
+* Input : - RCC_IT: specifies the interrupt pending bit to clear.
+* This parameter can be any combination of the following values:
+* - RCC_IT_LSIRDY: LSI ready interrupt
+* - RCC_IT_LSERDY: LSE ready interrupt
+* - RCC_IT_HSIRDY: HSI ready interrupt
+* - RCC_IT_HSERDY: HSE ready interrupt
+* - RCC_IT_PLLRDY: PLL ready interrupt
+* - RCC_IT_CSS: Clock Security System interrupt
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_ClearITPendingBit(u8 RCC_IT)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_CLEAR_IT(RCC_IT));
+
+ /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt
+ pending bits */
+ *(vu8 *) CIR_BYTE3_ADDRESS = RCC_IT;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_rtc.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_rtc.c new file mode 100755 index 0000000..e59f061 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_rtc.c @@ -0,0 +1,320 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_rtc.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the RTC firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_rtc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define CRL_CNF_Set ((u16)0x0010) /* Configuration Flag Enable Mask */
+#define CRL_CNF_Reset ((u16)0xFFEF) /* Configuration Flag Disable Mask */
+#define RTC_LSB_Mask ((u32)0x0000FFFF) /* RTC LSB Mask */
+#define PRLH_MSB_Mask ((u32)0x000F0000) /* RTC Prescaler MSB Mask */
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : RTC_ITConfig
+* Description : Enables or disables the specified RTC interrupts.
+* Input : - RTC_IT: specifies the RTC interrupts sources to be enabled
+* or disabled.
+* This parameter can be any combination of the following values:
+* - RTC_IT_OW: Overflow interrupt
+* - RTC_IT_ALR: Alarm interrupt
+* - RTC_IT_SEC: Second interrupt
+* - NewState: new state of the specified RTC interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_ITConfig(u16 RTC_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_RTC_IT(RTC_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ RTC->CRH |= RTC_IT;
+ }
+ else
+ {
+ RTC->CRH &= (u16)~RTC_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RTC_EnterConfigMode
+* Description : Enters the RTC configuration mode.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_EnterConfigMode(void)
+{
+ /* Set the CNF flag to enter in the Configuration Mode */
+ RTC->CRL |= CRL_CNF_Set;
+}
+
+/*******************************************************************************
+* Function Name : RTC_ExitConfigMode
+* Description : Exits from the RTC configuration mode.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_ExitConfigMode(void)
+{
+ /* Reset the CNF flag to exit from the Configuration Mode */
+ RTC->CRL &= CRL_CNF_Reset;
+}
+
+/*******************************************************************************
+* Function Name : RTC_GetCounter
+* Description : Gets the RTC counter value.
+* Input : None
+* Output : None
+* Return : RTC counter value.
+*******************************************************************************/
+u32 RTC_GetCounter(void)
+{
+ u16 tmp = 0;
+ tmp = RTC->CNTL;
+
+ return (((u32)RTC->CNTH << 16 ) | tmp) ;
+}
+
+/*******************************************************************************
+* Function Name : RTC_SetCounter
+* Description : Sets the RTC counter value.
+* Input : - CounterValue: RTC counter new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_SetCounter(u32 CounterValue)
+{
+ RTC_EnterConfigMode();
+
+ /* Set RTC COUNTER MSB word */
+ RTC->CNTH = CounterValue >> 16;
+ /* Set RTC COUNTER LSB word */
+ RTC->CNTL = (CounterValue & RTC_LSB_Mask);
+
+ RTC_ExitConfigMode();
+}
+
+/*******************************************************************************
+* Function Name : RTC_SetPrescaler
+* Description : Sets the RTC prescaler value.
+* Input : - PrescalerValue: RTC prescaler new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_SetPrescaler(u32 PrescalerValue)
+{
+ /* Check the parameters */
+ assert_param(IS_RTC_PRESCALER(PrescalerValue));
+
+ RTC_EnterConfigMode();
+
+ /* Set RTC PRESCALER MSB word */
+ RTC->PRLH = (PrescalerValue & PRLH_MSB_Mask) >> 16;
+ /* Set RTC PRESCALER LSB word */
+ RTC->PRLL = (PrescalerValue & RTC_LSB_Mask);
+
+ RTC_ExitConfigMode();
+}
+
+/*******************************************************************************
+* Function Name : RTC_SetAlarm
+* Description : Sets the RTC alarm value.
+* Input : - AlarmValue: RTC alarm new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_SetAlarm(u32 AlarmValue)
+{
+ RTC_EnterConfigMode();
+
+ /* Set the ALARM MSB word */
+ RTC->ALRH = AlarmValue >> 16;
+ /* Set the ALARM LSB word */
+ RTC->ALRL = (AlarmValue & RTC_LSB_Mask);
+
+ RTC_ExitConfigMode();
+}
+
+/*******************************************************************************
+* Function Name : RTC_GetDivider
+* Description : Gets the RTC divider value.
+* Input : None
+* Output : None
+* Return : RTC Divider value.
+*******************************************************************************/
+u32 RTC_GetDivider(void)
+{
+ u32 tmp = 0x00;
+
+ tmp = ((u32)RTC->DIVH & (u32)0x000F) << 16;
+ tmp |= RTC->DIVL;
+
+ return tmp;
+}
+
+/*******************************************************************************
+* Function Name : RTC_WaitForLastTask
+* Description : Waits until last write operation on RTC registers has finished.
+* This function must be called before any write to RTC registers.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_WaitForLastTask(void)
+{
+ /* Loop until RTOFF flag is set */
+ while ((RTC->CRL & RTC_FLAG_RTOFF) == (u16)RESET)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RTC_WaitForSynchro
+* Description : Waits until the RTC registers (RTC_CNT, RTC_ALR and RTC_PRL)
+* are synchronized with RTC APB clock.
+* This function must be called before any read operation after
+* an APB reset or an APB clock stop.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_WaitForSynchro(void)
+{
+ /* Clear RSF flag */
+ RTC->CRL &= (u16)~RTC_FLAG_RSF;
+
+ /* Loop until RSF flag is set */
+ while ((RTC->CRL & RTC_FLAG_RSF) == (u16)RESET)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RTC_GetFlagStatus
+* Description : Checks whether the specified RTC flag is set or not.
+* Input : - RTC_FLAG: specifies the flag to check.
+* This parameter can be one the following values:
+* - RTC_FLAG_RTOFF: RTC Operation OFF flag
+* - RTC_FLAG_RSF: Registers Synchronized flag
+* - RTC_FLAG_OW: Overflow flag
+* - RTC_FLAG_ALR: Alarm flag
+* - RTC_FLAG_SEC: Second flag
+* Output : None
+* Return : The new state of RTC_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus RTC_GetFlagStatus(u16 RTC_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_RTC_GET_FLAG(RTC_FLAG));
+
+ if ((RTC->CRL & RTC_FLAG) != (u16)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : RTC_ClearFlag
+* Description : Clears the RTC’s pending flags.
+* Input : - RTC_FLAG: specifies the flag to clear.
+* This parameter can be any combination of the following values:
+* - RTC_FLAG_RSF: Registers Synchronized flag. This flag
+* is cleared only after an APB reset or an APB Clock stop.
+* - RTC_FLAG_OW: Overflow flag
+* - RTC_FLAG_ALR: Alarm flag
+* - RTC_FLAG_SEC: Second flag
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_ClearFlag(u16 RTC_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_RTC_CLEAR_FLAG(RTC_FLAG));
+
+ /* Clear the coressponding RTC flag */
+ RTC->CRL &= (u16)~RTC_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : RTC_GetITStatus
+* Description : Checks whether the specified RTC interrupt has occured or not.
+* Input : - RTC_IT: specifies the RTC interrupts sources to check.
+* This parameter can be one of the following values:
+* - RTC_IT_OW: Overflow interrupt
+* - RTC_IT_ALR: Alarm interrupt
+* - RTC_IT_SEC: Second interrupt
+* Output : None
+* Return : The new state of the RTC_IT (SET or RESET).
+*******************************************************************************/
+ITStatus RTC_GetITStatus(u16 RTC_IT)
+{
+ ITStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_RTC_GET_IT(RTC_IT));
+
+ bitstatus = (ITStatus)(RTC->CRL & RTC_IT);
+
+ if (((RTC->CRH & RTC_IT) != (u16)RESET) && (bitstatus != (u16)RESET))
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : RTC_ClearITPendingBit
+* Description : Clears the RTC’s interrupt pending bits.
+* Input : - RTC_IT: specifies the interrupt pending bit to clear.
+* This parameter can be any combination of the following values:
+* - RTC_IT_OW: Overflow interrupt
+* - RTC_IT_ALR: Alarm interrupt
+* - RTC_IT_SEC: Second interrupt
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_ClearITPendingBit(u16 RTC_IT)
+{
+ /* Check the parameters */
+ assert_param(IS_RTC_IT(RTC_IT));
+
+ /* Clear the coressponding RTC pending bit */
+ RTC->CRL &= (u16)~RTC_IT;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_sdio.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_sdio.c new file mode 100755 index 0000000..5fb7292 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_sdio.c @@ -0,0 +1,832 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_sdio.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the SDIO firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_sdio.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* ------------ SDIO registers bit address in the alias region ----------- */
+#define SDIO_OFFSET (SDIO_BASE - PERIPH_BASE)
+
+/* --- CLKCR Register ---*/
+/* Alias word address of CLKEN bit */
+#define CLKCR_OFFSET (SDIO_OFFSET + 0x04)
+#define CLKEN_BitNumber 0x08
+#define CLKCR_CLKEN_BB (PERIPH_BB_BASE + (CLKCR_OFFSET * 32) + (CLKEN_BitNumber * 4))
+
+/* --- CMD Register ---*/
+/* Alias word address of SDIOSUSPEND bit */
+#define CMD_OFFSET (SDIO_OFFSET + 0x0C)
+#define SDIOSUSPEND_BitNumber 0x0B
+#define CMD_SDIOSUSPEND_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (SDIOSUSPEND_BitNumber * 4))
+
+/* Alias word address of ENCMDCOMPL bit */
+#define ENCMDCOMPL_BitNumber 0x0C
+#define CMD_ENCMDCOMPL_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ENCMDCOMPL_BitNumber * 4))
+
+/* Alias word address of NIEN bit */
+#define NIEN_BitNumber 0x0D
+#define CMD_NIEN_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (NIEN_BitNumber * 4))
+
+/* Alias word address of ATACMD bit */
+#define ATACMD_BitNumber 0x0E
+#define CMD_ATACMD_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ATACMD_BitNumber * 4))
+
+/* --- DCTRL Register ---*/
+/* Alias word address of DMAEN bit */
+#define DCTRL_OFFSET (SDIO_OFFSET + 0x2C)
+#define DMAEN_BitNumber 0x03
+#define DCTRL_DMAEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (DMAEN_BitNumber * 4))
+
+/* Alias word address of RWSTART bit */
+#define RWSTART_BitNumber 0x08
+#define DCTRL_RWSTART_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTART_BitNumber * 4))
+
+/* Alias word address of RWSTOP bit */
+#define RWSTOP_BitNumber 0x09
+#define DCTRL_RWSTOP_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTOP_BitNumber * 4))
+
+/* Alias word address of RWMOD bit */
+#define RWMOD_BitNumber 0x0A
+#define DCTRL_RWMOD_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWMOD_BitNumber * 4))
+
+/* Alias word address of SDIOEN bit */
+#define SDIOEN_BitNumber 0x0B
+#define DCTRL_SDIOEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (SDIOEN_BitNumber * 4))
+
+
+/* ---------------------- SDIO registers bit mask ------------------------ */
+/* --- CLKCR Register ---*/
+/* CLKCR register clear mask */
+#define CLKCR_CLEAR_MASK ((u32)0xFFFF8100)
+
+/* --- PWRCTRL Register ---*/
+/* SDIO PWRCTRL Mask */
+#define PWR_PWRCTRL_MASK ((u32)0xFFFFFFFC)
+
+/* --- DCTRL Register ---*/
+/* SDIO DCTRL Clear Mask */
+#define DCTRL_CLEAR_MASK ((u32)0xFFFFFF08)
+
+/* --- CMD Register ---*/
+/* CMD Register clear mask */
+#define CMD_CLEAR_MASK ((u32)0xFFFFF800)
+
+/* SDIO RESP Registers Address */
+#define SDIO_RESP_ADDR ((u32)(SDIO_BASE + 0x14))
+
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : SDIO_DeInit
+* Description : Deinitializes the SDIO peripheral registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_DeInit(void)
+{
+ SDIO->POWER = 0x00000000;
+ SDIO->CLKCR = 0x00000000;
+ SDIO->ARG = 0x00000000;
+ SDIO->CMD = 0x00000000;
+ SDIO->DTIMER = 0x00000000;
+ SDIO->DLEN = 0x00000000;
+ SDIO->DCTRL = 0x00000000;
+ SDIO->ICR = 0x00C007FF;
+ SDIO->MASK = 0x00000000;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_Init
+* Description : Initializes the SDIO peripheral according to the specified
+* parameters in the SDIO_InitStruct.
+* Input : SDIO_InitStruct : pointer to a SDIO_InitTypeDef structure
+* that contains the configuration information for the SDIO
+* peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_SDIO_CLOCK_EDGE(SDIO_InitStruct->SDIO_ClockEdge));
+ assert_param(IS_SDIO_CLOCK_BYPASS(SDIO_InitStruct->SDIO_ClockBypass));
+ assert_param(IS_SDIO_CLOCK_POWER_SAVE(SDIO_InitStruct->SDIO_ClockPowerSave));
+ assert_param(IS_SDIO_BUS_WIDE(SDIO_InitStruct->SDIO_BusWide));
+ assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(SDIO_InitStruct->SDIO_HardwareFlowControl));
+
+/*---------------------------- SDIO CLKCR Configuration ------------------------*/
+ /* Get the SDIO CLKCR value */
+ tmpreg = SDIO->CLKCR;
+
+ /* Clear CLKDIV, PWRSAV, BYPASS, WIDBUS, NEGEDGE, HWFC_EN bits */
+ tmpreg &= CLKCR_CLEAR_MASK;
+
+ /* Set CLKDIV bits according to SDIO_ClockDiv value */
+ /* Set PWRSAV bit according to SDIO_ClockPowerSave value */
+ /* Set BYPASS bit according to SDIO_ClockBypass value */
+ /* Set WIDBUS bits according to SDIO_BusWide value */
+ /* Set NEGEDGE bits according to SDIO_ClockEdge value */
+ /* Set HWFC_EN bits according to SDIO_HardwareFlowControl value */
+ tmpreg |= (SDIO_InitStruct->SDIO_ClockDiv | SDIO_InitStruct->SDIO_ClockPowerSave |
+ SDIO_InitStruct->SDIO_ClockBypass | SDIO_InitStruct->SDIO_BusWide |
+ SDIO_InitStruct->SDIO_ClockEdge | SDIO_InitStruct->SDIO_HardwareFlowControl);
+
+ /* Write to SDIO CLKCR */
+ SDIO->CLKCR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_StructInit
+* Description : Fills each SDIO_InitStruct member with its default value.
+* Input : SDIO_InitStruct: pointer to an SDIO_InitTypeDef structure which
+* will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct)
+{
+ /* SDIO_InitStruct members default value */
+ SDIO_InitStruct->SDIO_ClockDiv = 0x00;
+ SDIO_InitStruct->SDIO_ClockEdge = SDIO_ClockEdge_Rising;
+ SDIO_InitStruct->SDIO_ClockBypass = SDIO_ClockBypass_Disable;
+ SDIO_InitStruct->SDIO_ClockPowerSave = SDIO_ClockPowerSave_Disable;
+ SDIO_InitStruct->SDIO_BusWide = SDIO_BusWide_1b;
+ SDIO_InitStruct->SDIO_HardwareFlowControl = SDIO_HardwareFlowControl_Disable;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_ClockCmd
+* Description : Enables or disables the SDIO Clock.
+* Input : NewState: new state of the SDIO Clock.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_ClockCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CLKCR_CLKEN_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_SetPowerState
+* Description : Sets the power status of the controller.
+* Input : SDIO_PowerState: new state of the Power state.
+* This parameter can be one of the following values:
+* - SDIO_PowerState_OFF
+* - SDIO_PowerState_ON
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_SetPowerState(u32 SDIO_PowerState)
+{
+ /* Check the parameters */
+ assert_param(IS_SDIO_POWER_STATE(SDIO_PowerState));
+
+ SDIO->POWER &= PWR_PWRCTRL_MASK;
+ SDIO->POWER |= SDIO_PowerState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_GetPowerState
+* Description : Gets the power status of the controller.
+* Input : None
+* Output : None
+* Return : Power status of the controller. The returned value can
+* be one of the following:
+* - 0x00: Power OFF
+* - 0x02: Power UP
+* - 0x03: Power ON
+*******************************************************************************/
+u32 SDIO_GetPowerState(void)
+{
+ return (SDIO->POWER & (~PWR_PWRCTRL_MASK));
+}
+
+/*******************************************************************************
+* Function Name : SDIO_ITConfig
+* Description : Enables or disables the SDIO interrupts.
+* Input : - SDIO_IT: specifies the SDIO interrupt sources to be
+* enabled or disabled.
+* This parameter can be one or a combination of the following
+* values:
+* - SDIO_IT_CCRCFAIL: Command response received (CRC check
+* failed) interrupt
+* - SDIO_IT_DCRCFAIL: Data block sent/received (CRC check
+* failed) interrupt
+* - SDIO_IT_CTIMEOUT: Command response timeout interrupt
+* - SDIO_IT_DTIMEOUT: Data timeout interrupt
+* - SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt
+* - SDIO_IT_RXOVERR: Received FIFO overrun error interrupt
+* - SDIO_IT_CMDREND: Command response received (CRC check
+* passed) interrupt
+* - SDIO_IT_CMDSENT: Command sent (no response required)
+* interrupt
+* - SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is
+* zero) interrupt
+* - SDIO_IT_STBITERR: Start bit not detected on all data
+* signals in wide bus mode interrupt
+* - SDIO_IT_DBCKEND: Data block sent/received (CRC check
+* passed) interrupt
+* - SDIO_IT_CMDACT: Command transfer in progress interrupt
+* - SDIO_IT_TXACT: Data transmit in progress interrupt
+* - SDIO_IT_RXACT: Data receive in progress interrupt
+* - SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt
+* - SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt
+* - SDIO_IT_TXFIFOF: Transmit FIFO full interrupt
+* - SDIO_IT_RXFIFOF: Receive FIFO full interrupt
+* - SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt
+* - SDIO_IT_RXFIFOE: Receive FIFO empty interrupt
+* - SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt
+* - SDIO_IT_RXDAVL: Data available in receive FIFO interrupt
+* - SDIO_IT_SDIOIT: SD I/O interrupt received interrupt
+* - SDIO_IT_CEATAEND: CE-ATA command completion signal
+* received for CMD61 interrupt
+* - NewState: new state of the specified SDIO interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_ITConfig(u32 SDIO_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_SDIO_IT(SDIO_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the SDIO interrupts */
+ SDIO->MASK |= SDIO_IT;
+ }
+ else
+ {
+ /* Disable the SDIO interrupts */
+ SDIO->MASK &= ~SDIO_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SDIO_DMACmd
+* Description : Enables or disables the SDIO DMA request.
+* Input : NewState: new state of the selected SDIO DMA request.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_DMACmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) DCTRL_DMAEN_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_SendCommand
+* Description : Initializes the SDIO Command according to the specified
+* parameters in the SDIO_CmdInitStruct and send the command.
+* Input : SDIO_CmdInitStruct : pointer to a SDIO_CmdInitTypeDef
+* structure that contains the configuration information
+* for the SDIO command.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_SDIO_CMD_INDEX(SDIO_CmdInitStruct->SDIO_CmdIndex));
+ assert_param(IS_SDIO_RESPONSE(SDIO_CmdInitStruct->SDIO_Response));
+ assert_param(IS_SDIO_WAIT(SDIO_CmdInitStruct->SDIO_Wait));
+ assert_param(IS_SDIO_CPSM(SDIO_CmdInitStruct->SDIO_CPSM));
+
+/*---------------------------- SDIO ARG Configuration ------------------------*/
+ /* Set the SDIO Argument value */
+ SDIO->ARG = SDIO_CmdInitStruct->SDIO_Argument;
+
+/*---------------------------- SDIO CMD Configuration ------------------------*/
+ /* Get the SDIO CMD value */
+ tmpreg = SDIO->CMD;
+
+ /* Clear CMDINDEX, WAITRESP, WAITINT, WAITPEND, CPSMEN bits */
+ tmpreg &= CMD_CLEAR_MASK;
+ /* Set CMDINDEX bits according to SDIO_CmdIndex value */
+ /* Set WAITRESP bits according to SDIO_Response value */
+ /* Set WAITINT and WAITPEND bits according to SDIO_Wait value */
+ /* Set CPSMEN bits according to SDIO_CPSM value */
+ tmpreg |= (u32)SDIO_CmdInitStruct->SDIO_CmdIndex | SDIO_CmdInitStruct->SDIO_Response
+ | SDIO_CmdInitStruct->SDIO_Wait | SDIO_CmdInitStruct->SDIO_CPSM;
+
+ /* Write to SDIO CMD */
+ SDIO->CMD = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_CmdStructInit
+* Description : Fills each SDIO_CmdInitStruct member with its default value.
+* Input : SDIO_CmdInitStruct: pointer to an SDIO_CmdInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct)
+{
+ /* SDIO_CmdInitStruct members default value */
+ SDIO_CmdInitStruct->SDIO_Argument = 0x00;
+ SDIO_CmdInitStruct->SDIO_CmdIndex = 0x00;
+ SDIO_CmdInitStruct->SDIO_Response = SDIO_Response_No;
+ SDIO_CmdInitStruct->SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStruct->SDIO_CPSM = SDIO_CPSM_Disable;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_GetCommandResponse
+* Description : Returns command index of last command for which response
+* received.
+* Input : None
+* Output : None
+* Return : Returns the command index of the last command response received.
+*******************************************************************************/
+u8 SDIO_GetCommandResponse(void)
+{
+ return (u8)(SDIO->RESPCMD);
+}
+
+/*******************************************************************************
+* Function Name : SDIO_GetResponse
+* Description : Returns response received from the card for the last command.
+* Input : - SDIO_RESP: Specifies the SDIO response register.
+* This parameter can be one of the following values:
+* - SDIO_RESP1: Response Register 1
+* - SDIO_RESP2: Response Register 2
+* - SDIO_RESP3: Response Register 3
+* - SDIO_RESP4: Response Register 4
+* Output : None
+* Return : The Corresponding response register value.
+*******************************************************************************/
+u32 SDIO_GetResponse(u32 SDIO_RESP)
+{
+ /* Check the parameters */
+ assert_param(IS_SDIO_RESP(SDIO_RESP));
+
+ return (*(vu32 *)(SDIO_RESP_ADDR + SDIO_RESP));
+}
+
+/*******************************************************************************
+* Function Name : SDIO_DataConfig
+* Description : Initializes the SDIO data path according to the specified
+* parameters in the SDIO_DataInitStruct.
+* Input : SDIO_DataInitStruct : pointer to a SDIO_DataInitTypeDef
+* structure that contains the configuration information
+* for the SDIO command.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_SDIO_DATA_LENGTH(SDIO_DataInitStruct->SDIO_DataLength));
+ assert_param(IS_SDIO_BLOCK_SIZE(SDIO_DataInitStruct->SDIO_DataBlockSize));
+ assert_param(IS_SDIO_TRANSFER_DIR(SDIO_DataInitStruct->SDIO_TransferDir));
+ assert_param(IS_SDIO_TRANSFER_MODE(SDIO_DataInitStruct->SDIO_TransferMode));
+ assert_param(IS_SDIO_DPSM(SDIO_DataInitStruct->SDIO_DPSM));
+
+/*---------------------------- SDIO DTIMER Configuration ---------------------*/
+ /* Set the SDIO Data TimeOut value */
+ SDIO->DTIMER = SDIO_DataInitStruct->SDIO_DataTimeOut;
+
+/*---------------------------- SDIO DLEN Configuration -----------------------*/
+ /* Set the SDIO DataLength value */
+ SDIO->DLEN = SDIO_DataInitStruct->SDIO_DataLength;
+
+/*---------------------------- SDIO DCTRL Configuration ----------------------*/
+ /* Get the SDIO DCTRL value */
+ tmpreg = SDIO->DCTRL;
+
+ /* Clear DEN, DTMODE, DTDIR and DBCKSIZE bits */
+ tmpreg &= DCTRL_CLEAR_MASK;
+ /* Set DEN bit according to SDIO_DPSM value */
+ /* Set DTMODE bit according to SDIO_TransferMode value */
+ /* Set DTDIR bit according to SDIO_TransferDir value */
+ /* Set DBCKSIZE bits according to SDIO_DataBlockSize value */
+ tmpreg |= (u32)SDIO_DataInitStruct->SDIO_DataBlockSize | SDIO_DataInitStruct->SDIO_TransferDir
+ | SDIO_DataInitStruct->SDIO_TransferMode | SDIO_DataInitStruct->SDIO_DPSM;
+
+ /* Write to SDIO DCTRL */
+ SDIO->DCTRL = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_DataStructInit
+* Description : Fills each SDIO_DataInitStruct member with its default value.
+* Input : SDIO_DataInitStruct: pointer to an SDIO_DataInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct)
+{
+ /* SDIO_DataInitStruct members default value */
+ SDIO_DataInitStruct->SDIO_DataTimeOut = 0xFFFFFFFF;
+ SDIO_DataInitStruct->SDIO_DataLength = 0x00;
+ SDIO_DataInitStruct->SDIO_DataBlockSize = SDIO_DataBlockSize_1b;
+ SDIO_DataInitStruct->SDIO_TransferDir = SDIO_TransferDir_ToCard;
+ SDIO_DataInitStruct->SDIO_TransferMode = SDIO_TransferMode_Block;
+ SDIO_DataInitStruct->SDIO_DPSM = SDIO_DPSM_Disable;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_GetDataCounter
+* Description : Returns number of remaining data bytes to be transferred.
+* Input : None
+* Output : None
+* Return : Number of remaining data bytes to be transferred
+*******************************************************************************/
+u32 SDIO_GetDataCounter(void)
+{
+ return SDIO->DCOUNT;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_ReadData
+* Description : Read one data word from Rx FIFO.
+* Input : None
+* Output : None
+* Return : Data received
+*******************************************************************************/
+u32 SDIO_ReadData(void)
+{
+ return SDIO->FIFO;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_WriteData
+* Description : Write one data word to Tx FIFO.
+* Input : Data: 32-bit data word to write.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_WriteData(u32 Data)
+{
+ SDIO->FIFO = Data;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_GetFIFOCount
+* Description : Returns the number of words left to be written to or read
+* from FIFO.
+* Input : None
+* Output : None
+* Return : Remaining number of words.
+*******************************************************************************/
+u32 SDIO_GetFIFOCount(void)
+{
+ return SDIO->FIFOCNT;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_StartSDIOReadWait
+* Description : Starts the SD I/O Read Wait operation.
+* Input : NewState: new state of the Start SDIO Read Wait operation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_StartSDIOReadWait(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) DCTRL_RWSTART_BB = (u32) NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_StopSDIOReadWait
+* Description : Stops the SD I/O Read Wait operation.
+* Input : NewState: new state of the Stop SDIO Read Wait operation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_StopSDIOReadWait(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) DCTRL_RWSTOP_BB = (u32) NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_SetSDIOReadWaitMode
+* Description : Sets one of the two options of inserting read wait interval.
+* Input : SDIOReadWaitMode: SD I/O Read Wait operation mode.
+* This parametre can be:
+* - SDIO_ReadWaitMode_CLK: Read Wait control by stopping SDIOCLK
+* - SDIO_ReadWaitMode_DATA2: Read Wait control using SDIO_DATA2
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_SetSDIOReadWaitMode(u32 SDIO_ReadWaitMode)
+{
+ /* Check the parameters */
+ assert_param(IS_SDIO_READWAIT_MODE(SDIO_ReadWaitMode));
+
+ *(vu32 *) DCTRL_RWMOD_BB = SDIO_ReadWaitMode;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_SetSDIOOperation
+* Description : Enables or disables the SD I/O Mode Operation.
+* Input : NewState: new state of SDIO specific operation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_SetSDIOOperation(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) DCTRL_SDIOEN_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_SendSDIOSuspendCmd
+* Description : Enables or disables the SD I/O Mode suspend command sending.
+* Input : NewState: new state of the SD I/O Mode suspend command.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_SendSDIOSuspendCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CMD_SDIOSUSPEND_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_CommandCompletionCmd
+* Description : Enables or disables the command completion signal.
+* Input : NewState: new state of command completion signal.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_CommandCompletionCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CMD_ENCMDCOMPL_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_CEATAITCmd
+* Description : Enables or disables the CE-ATA interrupt.
+* Input : NewState: new state of CE-ATA interrupt.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_CEATAITCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CMD_NIEN_BB = (u32)((~((u32)NewState)) & ((u32)0x1));
+}
+
+/*******************************************************************************
+* Function Name : SDIO_SendCEATACmd
+* Description : Sends CE-ATA command (CMD61).
+* Input : NewState: new state of CE-ATA command.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_SendCEATACmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CMD_ATACMD_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_GetFlagStatus
+* Description : Checks whether the specified SDIO flag is set or not.
+* Input : SDIO_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - SDIO_FLAG_CCRCFAIL: Command response received (CRC check
+* failed)
+* - SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check
+* failed)
+* - SDIO_FLAG_CTIMEOUT: Command response timeout
+* - SDIO_FLAG_DTIMEOUT: Data timeou
+* - SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error
+* - SDIO_FLAG_RXOVERR: Received FIFO overrun error
+* - SDIO_FLAG_CMDREND: Command response received (CRC check
+* passed)
+* - SDIO_FLAG_CMDSENT: Command sent (no response required)
+* - SDIO_FLAG_DATAEND: Data end (data counter, SDIDCOUNT, is
+* zero)
+* - SDIO_FLAG_STBITERR: Start bit not detected on all data
+* signals in wide bus mode
+* - SDIO_FLAG_DBCKEND: Data block sent/received (CRC check
+* passed)
+* - SDIO_FLAG_CMDACT: Command transfer in progress
+* - SDIO_FLAG_TXACT: Data transmit in progress
+* - SDIO_FLAG_RXACT: Data receive in progress
+* - SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty
+* - SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full
+* - SDIO_FLAG_TXFIFOF: Transmit FIFO full
+* - SDIO_FLAG_RXFIFOF: Receive FIFO full
+* - SDIO_FLAG_TXFIFOE: Transmit FIFO empty
+* - SDIO_FLAG_RXFIFOE: Receive FIFO empty
+* - SDIO_FLAG_TXDAVL: Data available in transmit FIFO
+* - SDIO_FLAG_RXDAVL: Data available in receive FIFO
+* - SDIO_FLAG_SDIOIT: SD I/O interrupt received
+* - SDIO_FLAG_CEATAEND: CE-ATA command completion signal
+* received for CMD61
+* Output : None
+* Return : The new state of SDIO_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus SDIO_GetFlagStatus(u32 SDIO_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_SDIO_FLAG(SDIO_FLAG));
+
+ if ((SDIO->STA & SDIO_FLAG) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_ClearFlag
+* Description : Clears the SDIO's pending flags.
+* Input : SDIO_FLAG: specifies the flag to clear.
+* This parameter can be one or a combination of the following
+* values:
+* - SDIO_FLAG_CCRCFAIL: Command response received (CRC check
+* failed)
+* - SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check
+* failed)
+* - SDIO_FLAG_CTIMEOUT: Command response timeout
+* - SDIO_FLAG_DTIMEOUT: Data timeou
+* - SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error
+* - SDIO_FLAG_RXOVERR: Received FIFO overrun error
+* - SDIO_FLAG_CMDREND: Command response received (CRC check
+* passed)
+* - SDIO_FLAG_CMDSENT: Command sent (no response required)
+* - SDIO_FLAG_DATAEND: Data end (data counter, SDIDCOUNT, is
+* zero)
+* - SDIO_FLAG_STBITERR: Start bit not detected on all data
+* signals in wide bus mode
+* - SDIO_FLAG_DBCKEND: Data block sent/received (CRC check
+* passed)
+* - SDIO_FLAG_SDIOIT: SD I/O interrupt received
+* - SDIO_FLAG_CEATAEND: CE-ATA command completion signal
+* received for CMD61
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_ClearFlag(u32 SDIO_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_SDIO_CLEAR_FLAG(SDIO_FLAG));
+
+ SDIO->ICR = SDIO_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_GetITStatus
+* Description : Checks whether the specified SDIO interrupt has occurred or not.
+* Input : SDIO_IT: specifies the SDIO interrupt source to check.
+* This parameter can be one of the following values:
+* - SDIO_IT_CCRCFAIL: Command response received (CRC check
+* failed) interrupt
+* - SDIO_IT_DCRCFAIL: Data block sent/received (CRC check
+* failed) interrupt
+* - SDIO_IT_CTIMEOUT: Command response timeout interrupt
+* - SDIO_IT_DTIMEOUT: Data timeout interrupt
+* - SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt
+* - SDIO_IT_RXOVERR: Received FIFO overrun error interrupt
+* - SDIO_IT_CMDREND: Command response received (CRC check
+* passed) interrupt
+* - SDIO_IT_CMDSENT: Command sent (no response required)
+* interrupt
+* - SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is
+* zero) interrupt
+* - SDIO_IT_STBITERR: Start bit not detected on all data
+* signals in wide bus mode interrupt
+* - SDIO_IT_DBCKEND: Data block sent/received (CRC check
+* passed) interrupt
+* - SDIO_IT_CMDACT: Command transfer in progress interrupt
+* - SDIO_IT_TXACT: Data transmit in progress interrupt
+* - SDIO_IT_RXACT: Data receive in progress interrupt
+* - SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt
+* - SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt
+* - SDIO_IT_TXFIFOF: Transmit FIFO full interrupt
+* - SDIO_IT_RXFIFOF: Receive FIFO full interrupt
+* - SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt
+* - SDIO_IT_RXFIFOE: Receive FIFO empty interrupt
+* - SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt
+* - SDIO_IT_RXDAVL: Data available in receive FIFO interrupt
+* - SDIO_IT_SDIOIT: SD I/O interrupt received interrupt
+* - SDIO_IT_CEATAEND: CE-ATA command completion signal
+* received for CMD61 interrupt
+* Output : None
+* Return : The new state of SDIO_IT (SET or RESET).
+*******************************************************************************/
+ITStatus SDIO_GetITStatus(u32 SDIO_IT)
+{
+ ITStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_SDIO_GET_IT(SDIO_IT));
+
+ if ((SDIO->STA & SDIO_IT) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_ClearITPendingBit
+* Description : Clears the SDIO’s interrupt pending bits.
+* Input : SDIO_IT: specifies the interrupt pending bit to clear.
+* This parameter can be one or a combination of the following
+* values:
+* - SDIO_IT_CCRCFAIL: Command response received (CRC check
+* failed) interrupt
+* - SDIO_IT_DCRCFAIL: Data block sent/received (CRC check
+* failed) interrupt
+* - SDIO_IT_CTIMEOUT: Command response timeout interrupt
+* - SDIO_IT_DTIMEOUT: Data timeout interrupt
+* - SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt
+* - SDIO_IT_RXOVERR: Received FIFO overrun error interrupt
+* - SDIO_IT_CMDREND: Command response received (CRC check
+* passed) interrupt
+* - SDIO_IT_CMDSENT: Command sent (no response required)
+* interrupt
+* - SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is
+* zero) interrupt
+* - SDIO_IT_STBITERR: Start bit not detected on all data
+* signals in wide bus mode interrupt
+* - SDIO_IT_SDIOIT: SD I/O interrupt received interrupt
+* - SDIO_IT_CEATAEND: CE-ATA command completion signal
+* received for CMD61
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_ClearITPendingBit(u32 SDIO_IT)
+{
+ /* Check the parameters */
+ assert_param(IS_SDIO_CLEAR_IT(SDIO_IT));
+
+ SDIO->ICR = SDIO_IT;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_spi.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_spi.c new file mode 100755 index 0000000..e6a8d35 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_spi.c @@ -0,0 +1,886 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_spi.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the SPI firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_spi.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* SPI SPE mask */
+#define CR1_SPE_Set ((u16)0x0040)
+#define CR1_SPE_Reset ((u16)0xFFBF)
+
+/* I2S I2SE mask */
+#define I2SCFGR_I2SE_Set ((u16)0x0400)
+#define I2SCFGR_I2SE_Reset ((u16)0xFBFF)
+
+/* SPI CRCNext mask */
+#define CR1_CRCNext_Set ((u16)0x1000)
+
+/* SPI CRCEN mask */
+#define CR1_CRCEN_Set ((u16)0x2000)
+#define CR1_CRCEN_Reset ((u16)0xDFFF)
+
+/* SPI SSOE mask */
+#define CR2_SSOE_Set ((u16)0x0004)
+#define CR2_SSOE_Reset ((u16)0xFFFB)
+
+/* SPI registers Masks */
+#define CR1_CLEAR_Mask ((u16)0x3040)
+#define I2SCFGR_CLEAR_Mask ((u16)0xF040)
+
+/* SPI or I2S mode selection masks */
+#define SPI_Mode_Select ((u16)0xF7FF)
+#define I2S_Mode_Select ((u16)0x0800)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : SPI_I2S_DeInit
+* Description : Deinitializes the SPIx peripheral registers to their default
+* reset values (Affects also the I2Ss).
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_I2S_DeInit(SPI_TypeDef* SPIx)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+
+ switch (*(u32*)&SPIx)
+ {
+ case SPI1_BASE:
+ /* Enable SPI1 reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE);
+ /* Release SPI1 from reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, DISABLE);
+ break;
+
+ case SPI2_BASE:
+ /* Enable SPI2 reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE);
+ /* Release SPI2 from reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, DISABLE);
+ break;
+
+ case SPI3_BASE:
+ /* Enable SPI3 reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE);
+ /* Release SPI3 from reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, DISABLE);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_Init
+* Description : Initializes the SPIx peripheral according to the specified
+* parameters in the SPI_InitStruct.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - SPI_InitStruct: pointer to a SPI_InitTypeDef structure that
+* contains the configuration information for the specified
+* SPI peripheral.
+* Output : None
+* Return : None
+******************************************************************************/
+void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct)
+{
+ u16 tmpreg = 0;
+
+ /* check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+
+ /* Check the SPI parameters */
+ assert_param(IS_SPI_DIRECTION_MODE(SPI_InitStruct->SPI_Direction));
+ assert_param(IS_SPI_MODE(SPI_InitStruct->SPI_Mode));
+ assert_param(IS_SPI_DATASIZE(SPI_InitStruct->SPI_DataSize));
+ assert_param(IS_SPI_CPOL(SPI_InitStruct->SPI_CPOL));
+ assert_param(IS_SPI_CPHA(SPI_InitStruct->SPI_CPHA));
+ assert_param(IS_SPI_NSS(SPI_InitStruct->SPI_NSS));
+ assert_param(IS_SPI_BAUDRATE_PRESCALER(SPI_InitStruct->SPI_BaudRatePrescaler));
+ assert_param(IS_SPI_FIRST_BIT(SPI_InitStruct->SPI_FirstBit));
+ assert_param(IS_SPI_CRC_POLYNOMIAL(SPI_InitStruct->SPI_CRCPolynomial));
+
+/*---------------------------- SPIx CR1 Configuration ------------------------*/
+ /* Get the SPIx CR1 value */
+ tmpreg = SPIx->CR1;
+ /* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */
+ tmpreg &= CR1_CLEAR_Mask;
+ /* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler
+ master/salve mode, CPOL and CPHA */
+ /* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */
+ /* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */
+ /* Set LSBFirst bit according to SPI_FirstBit value */
+ /* Set BR bits according to SPI_BaudRatePrescaler value */
+ /* Set CPOL bit according to SPI_CPOL value */
+ /* Set CPHA bit according to SPI_CPHA value */
+ tmpreg |= (u16)((u32)SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode |
+ SPI_InitStruct->SPI_DataSize | SPI_InitStruct->SPI_CPOL |
+ SPI_InitStruct->SPI_CPHA | SPI_InitStruct->SPI_NSS |
+ SPI_InitStruct->SPI_BaudRatePrescaler | SPI_InitStruct->SPI_FirstBit);
+ /* Write to SPIx CR1 */
+ SPIx->CR1 = tmpreg;
+
+ /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */
+ SPIx->I2SCFGR &= SPI_Mode_Select;
+
+/*---------------------------- SPIx CRCPOLY Configuration --------------------*/
+ /* Write to SPIx CRCPOLY */
+ SPIx->CRCPR = SPI_InitStruct->SPI_CRCPolynomial;
+}
+
+/*******************************************************************************
+* Function Name : I2S_Init
+* Description : Initializes the SPIx peripheral according to the specified
+* parameters in the I2S_InitStruct.
+* Input : - SPIx: where x can be 2 or 3 to select the SPI peripheral
+* (configured in I2S mode).
+* - I2S_InitStruct: pointer to an I2S_InitTypeDef structure that
+* contains the configuration information for the specified
+* SPI peripheral configured in I2S mode.
+* Output : None
+* Return : None
+******************************************************************************/
+void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct)
+{
+ u16 tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1;
+ u32 tmp = 0;
+ RCC_ClocksTypeDef RCC_Clocks;
+
+ /* Check the I2S parameters */
+ assert_param(IS_SPI_23_PERIPH(SPIx));
+ assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode));
+ assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard));
+ assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat));
+ assert_param(IS_I2S_MCLK_OUTPUT(I2S_InitStruct->I2S_MCLKOutput));
+ assert_param(IS_I2S_AUDIO_FREQ(I2S_InitStruct->I2S_AudioFreq));
+ assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL));
+
+/*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/
+
+ /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */
+ SPIx->I2SCFGR &= I2SCFGR_CLEAR_Mask;
+ SPIx->I2SPR = 0x0002;
+
+ /* Get the I2SCFGR register value */
+ tmpreg = SPIx->I2SCFGR;
+
+ /* If the default value has to be written, reinitialize i2sdiv and i2sodd*/
+ if(I2S_InitStruct->I2S_AudioFreq == I2S_AudioFreq_Default)
+ {
+ i2sodd = (u16)0;
+ i2sdiv = (u16)2;
+ }
+ /* If the requested audio frequency is not the default, compute the prescaler */
+ else
+ {
+ /* Check the frame length (For the Prescaler computing) */
+ if(I2S_InitStruct->I2S_DataFormat == I2S_DataFormat_16b)
+ {
+ /* Packet length is 16 bits */
+ packetlength = 1;
+ }
+ else
+ {
+ /* Packet length is 32 bits */
+ packetlength = 2;
+ }
+ /* Get System Clock frequency */
+ RCC_GetClocksFreq(&RCC_Clocks);
+
+ /* Compute the Real divider depending on the MCLK output state with a flaoting point */
+ if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable)
+ {
+ /* MCLK output is enabled */
+ tmp = (u16)(((10 * RCC_Clocks.SYSCLK_Frequency) / (256 * I2S_InitStruct->I2S_AudioFreq)) + 5);
+ }
+ else
+ {
+ /* MCLK output is disabled */
+ tmp = (u16)(((10 * RCC_Clocks.SYSCLK_Frequency) / (32 * packetlength * I2S_InitStruct->I2S_AudioFreq)) + 5);
+ }
+
+ /* Remove the flaoting point */
+ tmp = tmp/10;
+
+ /* Check the parity of the divider */
+ i2sodd = (u16)(tmp & (u16)0x0001);
+
+ /* Compute the i2sdiv prescaler */
+ i2sdiv = (u16)((tmp - i2sodd) / 2);
+
+ /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */
+ i2sodd = (u16) (i2sodd << 8);
+ }
+
+ /* Test if the divider is 1 or 0 */
+ if ((i2sdiv < 2) || (i2sdiv > 0xFF))
+ {
+ /* Set the default values */
+ i2sdiv = 2;
+ i2sodd = 0;
+ }
+
+ /* Write to SPIx I2SPR register the computed value */
+ SPIx->I2SPR = (u16)(i2sdiv | i2sodd | I2S_InitStruct->I2S_MCLKOutput);
+
+ /* Configure the I2S with the SPI_InitStruct values */
+ tmpreg |= (u16)(I2S_Mode_Select | I2S_InitStruct->I2S_Mode | \
+ I2S_InitStruct->I2S_Standard | I2S_InitStruct->I2S_DataFormat | \
+ I2S_InitStruct->I2S_CPOL);
+
+ /* Write to SPIx I2SCFGR */
+ SPIx->I2SCFGR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : SPI_StructInit
+* Description : Fills each SPI_InitStruct member with its default value.
+* Input : - SPI_InitStruct : pointer to a SPI_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct)
+{
+/*--------------- Reset SPI init structure parameters values -----------------*/
+ /* Initialize the SPI_Direction member */
+ SPI_InitStruct->SPI_Direction = SPI_Direction_2Lines_FullDuplex;
+
+ /* initialize the SPI_Mode member */
+ SPI_InitStruct->SPI_Mode = SPI_Mode_Slave;
+
+ /* initialize the SPI_DataSize member */
+ SPI_InitStruct->SPI_DataSize = SPI_DataSize_8b;
+
+ /* Initialize the SPI_CPOL member */
+ SPI_InitStruct->SPI_CPOL = SPI_CPOL_Low;
+
+ /* Initialize the SPI_CPHA member */
+ SPI_InitStruct->SPI_CPHA = SPI_CPHA_1Edge;
+
+ /* Initialize the SPI_NSS member */
+ SPI_InitStruct->SPI_NSS = SPI_NSS_Hard;
+
+ /* Initialize the SPI_BaudRatePrescaler member */
+ SPI_InitStruct->SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2;
+
+ /* Initialize the SPI_FirstBit member */
+ SPI_InitStruct->SPI_FirstBit = SPI_FirstBit_MSB;
+
+ /* Initialize the SPI_CRCPolynomial member */
+ SPI_InitStruct->SPI_CRCPolynomial = 7;
+}
+
+/*******************************************************************************
+* Function Name : I2S_StructInit
+* Description : Fills each I2S_InitStruct member with its default value.
+* Input : - I2S_InitStruct : pointer to a I2S_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct)
+{
+/*--------------- Reset I2S init structure parameters values -----------------*/
+ /* Initialize the I2S_Mode member */
+ I2S_InitStruct->I2S_Mode = I2S_Mode_SlaveTx;
+
+ /* Initialize the I2S_Standard member */
+ I2S_InitStruct->I2S_Standard = I2S_Standard_Phillips;
+
+ /* Initialize the I2S_DataFormat member */
+ I2S_InitStruct->I2S_DataFormat = I2S_DataFormat_16b;
+
+ /* Initialize the I2S_MCLKOutput member */
+ I2S_InitStruct->I2S_MCLKOutput = I2S_MCLKOutput_Disable;
+
+ /* Initialize the I2S_AudioFreq member */
+ I2S_InitStruct->I2S_AudioFreq = I2S_AudioFreq_Default;
+
+ /* Initialize the I2S_CPOL member */
+ I2S_InitStruct->I2S_CPOL = I2S_CPOL_Low;
+}
+
+/*******************************************************************************
+* Function Name : SPI_Cmd
+* Description : Enables or disables the specified SPI peripheral.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - NewState: new state of the SPIx peripheral.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected SPI peripheral */
+ SPIx->CR1 |= CR1_SPE_Set;
+ }
+ else
+ {
+ /* Disable the selected SPI peripheral */
+ SPIx->CR1 &= CR1_SPE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2S_Cmd
+* Description : Enables or disables the specified SPI peripheral (in I2S mode).
+* Input : - SPIx: where x can be 2 or 3 to select the SPI peripheral.
+* - NewState: new state of the SPIx peripheral.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_23_PERIPH(SPIx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected SPI peripheral (in I2S mode) */
+ SPIx->I2SCFGR |= I2SCFGR_I2SE_Set;
+ }
+ else
+ {
+ /* Disable the selected SPI peripheral (in I2S mode) */
+ SPIx->I2SCFGR &= I2SCFGR_I2SE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_ITConfig
+* Description : Enables or disables the specified SPI/I2S interrupts.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - 2 or 3 in I2S mode
+* - SPI_I2S_IT: specifies the SPI/I2S interrupt source to be
+* enabled or disabled.
+* This parameter can be one of the following values:
+* - SPI_I2S_IT_TXE: Tx buffer empty interrupt mask
+* - SPI_I2S_IT_RXNE: Rx buffer not empty interrupt mask
+* - SPI_I2S_IT_ERR: Error interrupt mask
+* - NewState: new state of the specified SPI/I2S interrupt.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, u8 SPI_I2S_IT, FunctionalState NewState)
+{
+ u16 itpos = 0, itmask = 0 ;
+
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+ assert_param(IS_SPI_I2S_CONFIG_IT(SPI_I2S_IT));
+
+ /* Get the SPI/I2S IT index */
+ itpos = SPI_I2S_IT >> 4;
+ /* Set the IT mask */
+ itmask = (u16)((u16)1 << itpos);
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected SPI/I2S interrupt */
+ SPIx->CR2 |= itmask;
+ }
+ else
+ {
+ /* Disable the selected SPI/I2S interrupt */
+ SPIx->CR2 &= (u16)~itmask;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_DMACmd
+* Description : Enables or disables the SPIx/I2Sx DMA interface.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - 2 or 3 in I2S mode
+* - SPI_I2S_DMAReq: specifies the SPI/I2S DMA transfer request
+* to be enabled or disabled.
+* This parameter can be any combination of the following values:
+* - SPI_I2S_DMAReq_Tx: Tx buffer DMA transfer request
+* - SPI_I2S_DMAReq_Rx: Rx buffer DMA transfer request
+* - NewState: new state of the selected SPI/I2S DMA transfer
+* request.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, u16 SPI_I2S_DMAReq, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+ assert_param(IS_SPI_I2S_DMAREQ(SPI_I2S_DMAReq));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected SPI/I2S DMA requests */
+ SPIx->CR2 |= SPI_I2S_DMAReq;
+ }
+ else
+ {
+ /* Disable the selected SPI/I2S DMA requests */
+ SPIx->CR2 &= (u16)~SPI_I2S_DMAReq;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_SendData
+* Description : Transmits a Data through the SPIx/I2Sx peripheral.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - 2 or 3 in I2S mode
+* - Data : Data to be transmitted..
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_I2S_SendData(SPI_TypeDef* SPIx, u16 Data)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+
+ /* Write in the DR register the data to be sent */
+ SPIx->DR = Data;
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_ReceiveData
+* Description : Returns the most recent received data by the SPIx/I2Sx peripheral.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - 2 or 3 in I2S mode
+* Output : None
+* Return : The value of the received data.
+*******************************************************************************/
+u16 SPI_I2S_ReceiveData(SPI_TypeDef* SPIx)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+
+ /* Return the data in the DR register */
+ return SPIx->DR;
+}
+
+/*******************************************************************************
+* Function Name : SPI_NSSInternalSoftwareConfig
+* Description : Configures internally by software the NSS pin for the selected
+* SPI.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - SPI_NSSInternalSoft: specifies the SPI NSS internal state.
+* This parameter can be one of the following values:
+* - SPI_NSSInternalSoft_Set: Set NSS pin internally
+* - SPI_NSSInternalSoft_Reset: Reset NSS pin internally
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, u16 SPI_NSSInternalSoft)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_NSS_INTERNAL(SPI_NSSInternalSoft));
+
+ if (SPI_NSSInternalSoft != SPI_NSSInternalSoft_Reset)
+ {
+ /* Set NSS pin internally by software */
+ SPIx->CR1 |= SPI_NSSInternalSoft_Set;
+ }
+ else
+ {
+ /* Reset NSS pin internally by software */
+ SPIx->CR1 &= SPI_NSSInternalSoft_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_SSOutputCmd
+* Description : Enables or disables the SS output for the selected SPI.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - NewState: new state of the SPIx SS output.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected SPI SS output */
+ SPIx->CR2 |= CR2_SSOE_Set;
+ }
+ else
+ {
+ /* Disable the selected SPI SS output */
+ SPIx->CR2 &= CR2_SSOE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_DataSizeConfig
+* Description : Configures the data size for the selected SPI.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - SPI_DataSize: specifies the SPI data size.
+* This parameter can be one of the following values:
+* - SPI_DataSize_16b: Set data frame format to 16bit
+* - SPI_DataSize_8b: Set data frame format to 8bit
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_DataSizeConfig(SPI_TypeDef* SPIx, u16 SPI_DataSize)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_DATASIZE(SPI_DataSize));
+
+ /* Clear DFF bit */
+ SPIx->CR1 &= (u16)~SPI_DataSize_16b;
+ /* Set new DFF bit value */
+ SPIx->CR1 |= SPI_DataSize;
+}
+
+/*******************************************************************************
+* Function Name : SPI_TransmitCRC
+* Description : Transmit the SPIx CRC value.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_TransmitCRC(SPI_TypeDef* SPIx)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+
+ /* Enable the selected SPI CRC transmission */
+ SPIx->CR1 |= CR1_CRCNext_Set;
+}
+
+/*******************************************************************************
+* Function Name : SPI_CalculateCRC
+* Description : Enables or disables the CRC value calculation of the
+* transfered bytes.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - NewState: new state of the SPIx CRC value calculation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected SPI CRC calculation */
+ SPIx->CR1 |= CR1_CRCEN_Set;
+ }
+ else
+ {
+ /* Disable the selected SPI CRC calculation */
+ SPIx->CR1 &= CR1_CRCEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_GetCRC
+* Description : Returns the transmit or the receive CRC register value for
+* the specified SPI.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - SPI_CRC: specifies the CRC register to be read.
+* This parameter can be one of the following values:
+* - SPI_CRC_Tx: Selects Tx CRC register
+* - SPI_CRC_Rx: Selects Rx CRC register
+* Output : None
+* Return : The selected CRC register value..
+*******************************************************************************/
+u16 SPI_GetCRC(SPI_TypeDef* SPIx, u8 SPI_CRC)
+{
+ u16 crcreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_CRC(SPI_CRC));
+
+ if (SPI_CRC != SPI_CRC_Rx)
+ {
+ /* Get the Tx CRC register */
+ crcreg = SPIx->TXCRCR;
+ }
+ else
+ {
+ /* Get the Rx CRC register */
+ crcreg = SPIx->RXCRCR;
+ }
+
+ /* Return the selected CRC register */
+ return crcreg;
+}
+
+/*******************************************************************************
+* Function Name : SPI_GetCRCPolynomial
+* Description : Returns the CRC Polynomial register value for the specified SPI.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* Output : None
+* Return : The CRC Polynomial register value.
+*******************************************************************************/
+u16 SPI_GetCRCPolynomial(SPI_TypeDef* SPIx)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+
+ /* Return the CRC polynomial register */
+ return SPIx->CRCPR;
+}
+
+/*******************************************************************************
+* Function Name : SPI_BiDirectionalLineConfig
+* Description : Selects the data transfer direction in bi-directional mode
+* for the specified SPI.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - SPI_Direction: specifies the data transfer direction in
+* bi-directional mode.
+* This parameter can be one of the following values:
+* - SPI_Direction_Tx: Selects Tx transmission direction
+* - SPI_Direction_Rx: Selects Rx receive direction
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, u16 SPI_Direction)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_DIRECTION(SPI_Direction));
+
+ if (SPI_Direction == SPI_Direction_Tx)
+ {
+ /* Set the Tx only mode */
+ SPIx->CR1 |= SPI_Direction_Tx;
+ }
+ else
+ {
+ /* Set the Rx only mode */
+ SPIx->CR1 &= SPI_Direction_Rx;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_GetFlagStatus
+* Description : Checks whether the specified SPI/I2S flag is set or not.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - 2 or 3 in I2S mode
+* - SPI_I2S_FLAG: specifies the SPI/I2S flag to check.
+* This parameter can be one of the following values:
+* - SPI_I2S_FLAG_TXE: Transmit buffer empty flag.
+* - SPI_I2S_FLAG_RXNE: Receive buffer not empty flag.
+* - SPI_I2S_FLAG_BSY: Busy flag.
+* - SPI_I2S_FLAG_OVR: Overrun flag.
+* - SPI_FLAG_MODF: Mode Fault flag.
+* - SPI_FLAG_CRCERR: CRC Error flag.
+* - I2S_FLAG_UDR: Underrun Error flag.
+* - I2S_FLAG_CHSIDE: Channel Side flag.
+* Output : None
+* Return : The new state of SPI_I2S_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, u16 SPI_I2S_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_I2S_GET_FLAG(SPI_I2S_FLAG));
+
+ /* Check the status of the specified SPI/I2S flag */
+ if ((SPIx->SR & SPI_I2S_FLAG) != (u16)RESET)
+ {
+ /* SPI_I2S_FLAG is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* SPI_I2S_FLAG is reset */
+ bitstatus = RESET;
+ }
+ /* Return the SPI_I2S_FLAG status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_ClearFlag
+* Description : Clears the SPIx/I2Sx pending flags.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - 2 or 3 in I2S mode
+* - SPI_I2S_FLAG: specifies the SPI/I2S flag to clear.
+* This parameter can be one of the following values:
+* - SPI_I2S_FLAG_OVR: Overrun flag
+* - SPI_FLAG_MODF: Mode Fault flag.
+* - SPI_FLAG_CRCERR: CRC Error flag.
+* - I2S_FLAG_UDR: Underrun Error flag.
+* Note: Before clearing OVR flag, it is mandatory to read
+* SPI_I2S_DR register, so that the last data is not lost.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, u16 SPI_I2S_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_I2S_CLEAR_FLAG(SPI_I2S_FLAG));
+
+ /* SPI_FLAG_MODF flag clear */
+ if(SPI_I2S_FLAG == SPI_FLAG_MODF)
+ {
+ /* Read SR register */
+ (void)SPIx->SR;
+
+ /* Write on CR1 register */
+ SPIx->CR1 |= CR1_SPE_Set;
+ }
+ /* SPI_I2S_FLAG_OVR flag or I2S_FLAG_UDR flag clear */
+ else if ((SPI_I2S_FLAG == SPI_I2S_FLAG_OVR) || (SPI_I2S_FLAG == I2S_FLAG_UDR))
+ {
+ /* Read SR register (Before clearing OVR flag, it is mandatory to read
+ SPI_I2S_DR register)*/
+ (void)SPIx->SR;
+ }
+ else /* SPI_FLAG_CRCERR flag clear */
+ {
+ /* Clear the selected SPI flag */
+ SPIx->SR = (u16)~SPI_I2S_FLAG;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_GetITStatus
+* Description : Checks whether the specified SPI/I2S interrupt has occurred or not.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - 2 or 3 in I2S mode
+* - SPI_I2S_IT: specifies the SPI/I2S interrupt source to check.
+* This parameter can be one of the following values:
+* - SPI_I2S_IT_TXE: Transmit buffer empty interrupt.
+* - SPI_I2S_IT_RXNE: Receive buffer not empty interrupt.
+* - SPI_I2S_IT_OVR: Overrun interrupt.
+* - SPI_IT_MODF: Mode Fault interrupt.
+* - SPI_IT_CRCERR: CRC Error interrupt.
+* - I2S_IT_UDR: Underrun Error interrupt.
+* Output : None
+* Return : The new state of SPI_I2S_IT (SET or RESET).
+*******************************************************************************/
+ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, u8 SPI_I2S_IT)
+{
+ ITStatus bitstatus = RESET;
+ u16 itpos = 0, itmask = 0, enablestatus = 0;
+
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_I2S_GET_IT(SPI_I2S_IT));
+
+ /* Get the SPI/I2S IT index */
+ itpos = (u16)((u16)0x01 << (SPI_I2S_IT & (u8)0x0F));
+
+ /* Get the SPI/I2S IT mask */
+ itmask = SPI_I2S_IT >> 4;
+ /* Set the IT mask */
+ itmask = (u16)((u16)0x01 << itmask);
+ /* Get the SPI_I2S_IT enable bit status */
+ enablestatus = (SPIx->CR2 & itmask) ;
+
+ /* Check the status of the specified SPI/I2S interrupt */
+ if (((SPIx->SR & itpos) != (u16)RESET) && enablestatus)
+ {
+ /* SPI_I2S_IT is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* SPI_I2S_IT is reset */
+ bitstatus = RESET;
+ }
+ /* Return the SPI_I2S_IT status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_ClearITPendingBit
+* Description : Clears the SPIx/I2Sx interrupt pending bits.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - 2 or 3 in I2S mode
+* - SPI_I2S_IT: specifies the SPI/I2S interrupt pending bit to clear.
+* This parameter can be one of the following values:
+* - SPI_I2S_IT_OVR: Overrun interrupt.
+* - SPI_IT_MODF: Mode Fault interrupt.
+* - SPI_IT_CRCERR: CRC Error interrupt.
+* - I2S_IT_UDR: Underrun Error interrupt.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, u8 SPI_I2S_IT)
+{
+ u16 itpos = 0;
+
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_I2S_CLEAR_IT(SPI_I2S_IT));
+
+ /* SPI_IT_MODF pending bit clear */
+ if(SPI_I2S_IT == SPI_IT_MODF)
+ {
+ /* Read SR register */
+ (void)SPIx->SR;
+ /* Write on CR1 register */
+ SPIx->CR1 |= CR1_SPE_Set;
+ }
+ /* SPI_I2S_IT_OVR or I2S_IT_UDR pending bit clear */
+ else if((SPI_I2S_IT == SPI_I2S_IT_OVR) || (SPI_I2S_IT == I2S_IT_UDR))
+ {
+ /* Read SR register */
+ (void)(SPIx->SR);
+ }
+ else /* SPI_IT_CRCERR pending bit clear */
+ {
+ /* Get the SPI/I2S IT index */
+ itpos = (u16)((u16)0x01 << (SPI_I2S_IT & (u8)0x0F));
+ /* Clear the selected SPI/I2S interrupt pending bits */
+ SPIx->SR = (u16)~itpos;
+ }
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_systick.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_systick.c new file mode 100755 index 0000000..29ee88a --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_systick.c @@ -0,0 +1,181 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_systick.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the SysTick firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_systick.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ---------------------- SysTick registers bit mask -------------------- */
+/* CTRL TICKINT Mask */
+#define CTRL_TICKINT_Set ((u32)0x00000002)
+#define CTRL_TICKINT_Reset ((u32)0xFFFFFFFD)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : SysTick_CLKSourceConfig
+* Description : Configures the SysTick clock source.
+* Input : - SysTick_CLKSource: specifies the SysTick clock source.
+* This parameter can be one of the following values:
+* - SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8
+* selected as SysTick clock source.
+* - SysTick_CLKSource_HCLK: AHB clock selected as
+* SysTick clock source.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTick_CLKSourceConfig(u32 SysTick_CLKSource)
+{
+ /* Check the parameters */
+ assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource));
+
+ if (SysTick_CLKSource == SysTick_CLKSource_HCLK)
+ {
+ SysTick->CTRL |= SysTick_CLKSource_HCLK;
+ }
+ else
+ {
+ SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SysTick_SetReload
+* Description : Sets SysTick Reload value.
+* Input : - Reload: SysTick Reload new value.
+* This parameter must be a number between 1 and 0xFFFFFF.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTick_SetReload(u32 Reload)
+{
+ /* Check the parameters */
+ assert_param(IS_SYSTICK_RELOAD(Reload));
+
+ SysTick->LOAD = Reload;
+}
+
+/*******************************************************************************
+* Function Name : SysTick_CounterCmd
+* Description : Enables or disables the SysTick counter.
+* Input : - SysTick_Counter: new state of the SysTick counter.
+* This parameter can be one of the following values:
+* - SysTick_Counter_Disable: Disable counter
+* - SysTick_Counter_Enable: Enable counter
+* - SysTick_Counter_Clear: Clear counter value to 0
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTick_CounterCmd(u32 SysTick_Counter)
+{
+ /* Check the parameters */
+ assert_param(IS_SYSTICK_COUNTER(SysTick_Counter));
+
+ if (SysTick_Counter == SysTick_Counter_Enable)
+ {
+ SysTick->CTRL |= SysTick_Counter_Enable;
+ }
+ else if (SysTick_Counter == SysTick_Counter_Disable)
+ {
+ SysTick->CTRL &= SysTick_Counter_Disable;
+ }
+ else /* SysTick_Counter == SysTick_Counter_Clear */
+ {
+ SysTick->VAL = SysTick_Counter_Clear;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SysTick_ITConfig
+* Description : Enables or disables the SysTick Interrupt.
+* Input : - NewState: new state of the SysTick Interrupt.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTick_ITConfig(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ SysTick->CTRL |= CTRL_TICKINT_Set;
+ }
+ else
+ {
+ SysTick->CTRL &= CTRL_TICKINT_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SysTick_GetCounter
+* Description : Gets SysTick counter value.
+* Input : None
+* Output : None
+* Return : SysTick current value
+*******************************************************************************/
+u32 SysTick_GetCounter(void)
+{
+ return(SysTick->VAL);
+}
+
+/*******************************************************************************
+* Function Name : SysTick_GetFlagStatus
+* Description : Checks whether the specified SysTick flag is set or not.
+* Input : - SysTick_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - SysTick_FLAG_COUNT
+* - SysTick_FLAG_SKEW
+* - SysTick_FLAG_NOREF
+* Output : None
+* Return : None
+*******************************************************************************/
+FlagStatus SysTick_GetFlagStatus(u8 SysTick_FLAG)
+{
+ u32 statusreg = 0, tmp = 0 ;
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_SYSTICK_FLAG(SysTick_FLAG));
+
+ /* Get the SysTick register index */
+ tmp = SysTick_FLAG >> 3;
+
+ if (tmp == 2) /* The flag to check is in CTRL register */
+ {
+ statusreg = SysTick->CTRL;
+ }
+ else /* The flag to check is in CALIB register */
+ {
+ statusreg = SysTick->CALIB;
+ }
+
+ if ((statusreg & ((u32)1 << SysTick_FLAG)) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_tim.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_tim.c new file mode 100755 index 0000000..812cab0 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_tim.c @@ -0,0 +1,3220 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_tim.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the TIM firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_tim.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ---------------------- TIM registers bit mask ------------------------ */
+#define CR1_CEN_Set ((u16)0x0001)
+#define CR1_CEN_Reset ((u16)0x03FE)
+#define CR1_UDIS_Set ((u16)0x0002)
+#define CR1_UDIS_Reset ((u16)0x03FD)
+#define CR1_URS_Set ((u16)0x0004)
+#define CR1_URS_Reset ((u16)0x03FB)
+#define CR1_OPM_Reset ((u16)0x03F7)
+#define CR1_CounterMode_Mask ((u16)0x038F)
+#define CR1_ARPE_Set ((u16)0x0080)
+#define CR1_ARPE_Reset ((u16)0x037F)
+#define CR1_CKD_Mask ((u16)0x00FF)
+
+#define CR2_CCPC_Set ((u16)0x0001)
+#define CR2_CCPC_Reset ((u16)0xFFFE)
+#define CR2_CCUS_Set ((u16)0x0004)
+#define CR2_CCUS_Reset ((u16)0xFFFB)
+#define CR2_CCDS_Set ((u16)0x0008)
+#define CR2_CCDS_Reset ((u16)0xFFF7)
+#define CR2_MMS_Mask ((u16)0xFF8F)
+#define CR2_TI1S_Set ((u16)0x0080)
+#define CR2_TI1S_Reset ((u16)0xFF7F)
+#define CR2_OIS1_Reset ((u16)0x7EFF)
+#define CR2_OIS1N_Reset ((u16)0x7DFF)
+#define CR2_OIS2_Reset ((u16)0x7BFF)
+#define CR2_OIS2N_Reset ((u16)0x77FF)
+#define CR2_OIS3_Reset ((u16)0x6FFF)
+#define CR2_OIS3N_Reset ((u16)0x5FFF)
+#define CR2_OIS4_Reset ((u16)0x3FFF)
+
+#define SMCR_SMS_Mask ((u16)0xFFF8)
+#define SMCR_ETR_Mask ((u16)0x00FF)
+#define SMCR_TS_Mask ((u16)0xFF8F)
+#define SMCR_MSM_Reset ((u16)0xFF7F)
+#define SMCR_ECE_Set ((u16)0x4000)
+
+#define CCMR_CC13S_Mask ((u16)0xFFFC)
+#define CCMR_CC24S_Mask ((u16)0xFCFF)
+#define CCMR_TI13Direct_Set ((u16)0x0001)
+#define CCMR_TI24Direct_Set ((u16)0x0100)
+#define CCMR_OC13FE_Reset ((u16)0xFFFB)
+#define CCMR_OC24FE_Reset ((u16)0xFBFF)
+#define CCMR_OC13PE_Reset ((u16)0xFFF7)
+#define CCMR_OC24PE_Reset ((u16)0xF7FF)
+#define CCMR_OC13M_Mask ((u16)0xFF8F)
+#define CCMR_OC24M_Mask ((u16)0x8FFF)
+
+#define CCMR_OC13CE_Reset ((u16)0xFF7F)
+#define CCMR_OC24CE_Reset ((u16)0x7FFF)
+
+#define CCMR_IC13PSC_Mask ((u16)0xFFF3)
+#define CCMR_IC24PSC_Mask ((u16)0xF3FF)
+#define CCMR_IC13F_Mask ((u16)0xFF0F)
+#define CCMR_IC24F_Mask ((u16)0x0FFF)
+
+#define CCMR_Offset ((u16)0x0018)
+#define CCER_CCE_Set ((u16)0x0001)
+#define CCER_CCNE_Set ((u16)0x0004)
+
+#define CCER_CC1P_Reset ((u16)0xFFFD)
+#define CCER_CC2P_Reset ((u16)0xFFDF)
+#define CCER_CC3P_Reset ((u16)0xFDFF)
+#define CCER_CC4P_Reset ((u16)0xDFFF)
+
+#define CCER_CC1NP_Reset ((u16)0xFFF7)
+#define CCER_CC2NP_Reset ((u16)0xFF7F)
+#define CCER_CC3NP_Reset ((u16)0xF7FF)
+
+#define CCER_CC1E_Set ((u16)0x0001)
+#define CCER_CC1E_Reset ((u16)0xFFFE)
+
+#define CCER_CC1NE_Reset ((u16)0xFFFB)
+
+#define CCER_CC2E_Set ((u16)0x0010)
+#define CCER_CC2E_Reset ((u16)0xFFEF)
+
+#define CCER_CC2NE_Reset ((u16)0xFFBF)
+
+#define CCER_CC3E_Set ((u16)0x0100)
+#define CCER_CC3E_Reset ((u16)0xFEFF)
+
+#define CCER_CC3NE_Reset ((u16)0xFBFF)
+
+#define CCER_CC4E_Set ((u16)0x1000)
+#define CCER_CC4E_Reset ((u16)0xEFFF)
+
+#define BDTR_MOE_Set ((u16)0x8000)
+#define BDTR_MOE_Reset ((u16)0x7FFF)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+static void TI1_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter);
+static void TI2_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter);
+static void TI3_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter);
+static void TI4_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter);
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : TIM_DeInit
+* Description : Deinitializes the TIMx peripheral registers to their default
+* reset values.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_DeInit(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+
+ switch (*(u32*)&TIMx)
+ {
+ case TIM1_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, DISABLE);
+ break;
+
+ case TIM2_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, DISABLE);
+ break;
+
+ case TIM3_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, DISABLE);
+ break;
+
+ case TIM4_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, DISABLE);
+ break;
+
+ case TIM5_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, DISABLE);
+ break;
+
+ case TIM6_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, DISABLE);
+ break;
+
+ case TIM7_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, DISABLE);
+ break;
+
+ case TIM8_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, DISABLE);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_TimeBaseInit
+* Description : Initializes the TIMx Time Base Unit peripheral according to
+* the specified parameters in the TIM_TimeBaseInitStruct.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_TimeBaseInitStruct: pointer to a TIM_TimeBaseInitTypeDef
+* structure that contains the configuration information for
+* the specified TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_COUNTER_MODE(TIM_TimeBaseInitStruct->TIM_CounterMode));
+ assert_param(IS_TIM_CKD_DIV(TIM_TimeBaseInitStruct->TIM_ClockDivision));
+
+ /* Select the Counter Mode and set the clock division */
+ TIMx->CR1 &= CR1_CKD_Mask & CR1_CounterMode_Mask;
+ TIMx->CR1 |= (u32)TIM_TimeBaseInitStruct->TIM_ClockDivision |
+ TIM_TimeBaseInitStruct->TIM_CounterMode;
+ /* Set the Autoreload value */
+ TIMx->ARR = TIM_TimeBaseInitStruct->TIM_Period ;
+
+ /* Set the Prescaler value */
+ TIMx->PSC = TIM_TimeBaseInitStruct->TIM_Prescaler;
+
+ /* Generate an update event to reload the Prescaler value immediatly */
+ TIMx->EGR = TIM_PSCReloadMode_Immediate;
+
+ if (((*(u32*)&TIMx) == TIM1_BASE) || ((*(u32*)&TIMx) == TIM8_BASE))
+ {
+ /* Set the Repetition Counter value */
+ TIMx->RCR = TIM_TimeBaseInitStruct->TIM_RepetitionCounter;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC1Init
+* Description : Initializes the TIMx Channel1 according to the specified
+* parameters in the TIM_OCInitStruct.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure
+* that contains the configuration information for the specified
+* TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+ u16 tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+ assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));
+
+ /* Disable the Channel 1: Reset the CC1E Bit */
+ TIMx->CCER &= CCER_CC1E_Reset;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = TIMx->CCER;
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = TIMx->CR2;
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmrx = TIMx->CCMR1;
+
+ /* Reset the Output Compare Mode Bits */
+ tmpccmrx &= CCMR_OC13M_Mask;
+
+ /* Select the Output Compare Mode */
+ tmpccmrx |= TIM_OCInitStruct->TIM_OCMode;
+
+ /* Reset the Output Polarity level */
+ tmpccer &= CCER_CC1P_Reset;
+
+ /* Set the Output Compare Polarity */
+ tmpccer |= TIM_OCInitStruct->TIM_OCPolarity;
+
+ /* Set the Output State */
+ tmpccer |= TIM_OCInitStruct->TIM_OutputState;
+
+ /* Set the Capture Compare Register value */
+ TIMx->CCR1 = TIM_OCInitStruct->TIM_Pulse;
+
+ if((*(u32*)&TIMx == TIM1_BASE) || (*(u32*)&TIMx == TIM8_BASE))
+ {
+ assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState));
+ assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity));
+ assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState));
+ assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+
+ /* Reset the Output N Polarity level */
+ tmpccer &= CCER_CC1NP_Reset;
+
+ /* Set the Output N Polarity */
+ tmpccer |= TIM_OCInitStruct->TIM_OCNPolarity;
+
+ /* Reset the Output N State */
+ tmpccer &= CCER_CC1NE_Reset;
+
+ /* Set the Output N State */
+ tmpccer |= TIM_OCInitStruct->TIM_OutputNState;
+
+ /* Reset the Ouput Compare and Output Compare N IDLE State */
+ tmpcr2 &= CR2_OIS1_Reset;
+ tmpcr2 &= CR2_OIS1N_Reset;
+
+ /* Set the Output Idle state */
+ tmpcr2 |= TIM_OCInitStruct->TIM_OCIdleState;
+
+ /* Set the Output N Idle state */
+ tmpcr2 |= TIM_OCInitStruct->TIM_OCNIdleState;
+ }
+ /* Write to TIMx CR2 */
+ TIMx->CR2 = tmpcr2;
+
+ /* Write to TIMx CCMR1 */
+ TIMx->CCMR1 = tmpccmrx;
+
+ /* Write to TIMx CCER */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC2Init
+* Description : Initializes the TIMx Channel2 according to the specified
+* parameters in the TIM_OCInitStruct.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure
+* that contains the configuration information for the specified
+* TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+ u16 tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+ assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));
+
+ /* Disable the Channel 2: Reset the CC2E Bit */
+ TIMx->CCER &= CCER_CC2E_Reset;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = TIMx->CCER;
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = TIMx->CR2;
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmrx = TIMx->CCMR1;
+
+ /* Reset the Output Compare Mode Bits */
+ tmpccmrx &= CCMR_OC24M_Mask;
+
+ /* Select the Output Compare Mode */
+ tmpccmrx |= (u16)(TIM_OCInitStruct->TIM_OCMode << 8);
+
+ /* Reset the Output Polarity level */
+ tmpccer &= CCER_CC2P_Reset;
+
+ /* Set the Output Compare Polarity */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OCPolarity << 4);
+
+ /* Set the Output State */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OutputState << 4);
+
+ /* Set the Capture Compare Register value */
+ TIMx->CCR2 = TIM_OCInitStruct->TIM_Pulse;
+
+ if((*(u32*)&TIMx == TIM1_BASE) || (*(u32*)&TIMx == TIM8_BASE))
+ {
+ assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState));
+ assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity));
+ assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState));
+ assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+
+ /* Reset the Output N Polarity level */
+ tmpccer &= CCER_CC2NP_Reset;
+
+ /* Set the Output N Polarity */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OCNPolarity << 4);
+
+ /* Reset the Output N State */
+ tmpccer &= CCER_CC2NE_Reset;
+
+ /* Set the Output N State */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OutputNState << 4);
+
+ /* Reset the Ouput Compare and Output Compare N IDLE State */
+ tmpcr2 &= CR2_OIS2_Reset;
+ tmpcr2 &= CR2_OIS2N_Reset;
+
+ /* Set the Output Idle state */
+ tmpcr2 |= (u16)(TIM_OCInitStruct->TIM_OCIdleState << 2);
+
+ /* Set the Output N Idle state */
+ tmpcr2 |= (u16)(TIM_OCInitStruct->TIM_OCNIdleState << 2);
+ }
+
+ /* Write to TIMx CR2 */
+ TIMx->CR2 = tmpcr2;
+
+ /* Write to TIMx CCMR1 */
+ TIMx->CCMR1 = tmpccmrx;
+
+ /* Write to TIMx CCER */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC3Init
+* Description : Initializes the TIMx Channel3 according to the specified
+* parameters in the TIM_OCInitStruct.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure
+* that contains the configuration information for the specified
+* TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+ u16 tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+ assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));
+
+ /* Disable the Channel 2: Reset the CC2E Bit */
+ TIMx->CCER &= CCER_CC3E_Reset;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = TIMx->CCER;
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = TIMx->CR2;
+
+ /* Get the TIMx CCMR2 register value */
+ tmpccmrx = TIMx->CCMR2;
+
+ /* Reset the Output Compare Mode Bits */
+ tmpccmrx &= CCMR_OC13M_Mask;
+
+ /* Select the Output Compare Mode */
+ tmpccmrx |= TIM_OCInitStruct->TIM_OCMode;
+
+ /* Reset the Output Polarity level */
+ tmpccer &= CCER_CC3P_Reset;
+
+ /* Set the Output Compare Polarity */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OCPolarity << 8);
+
+ /* Set the Output State */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OutputState << 8);
+
+ /* Set the Capture Compare Register value */
+ TIMx->CCR3 = TIM_OCInitStruct->TIM_Pulse;
+
+ if((*(u32*)&TIMx == TIM1_BASE) || (*(u32*)&TIMx == TIM8_BASE))
+ {
+ assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState));
+ assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity));
+ assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState));
+ assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+
+ /* Reset the Output N Polarity level */
+ tmpccer &= CCER_CC3NP_Reset;
+
+ /* Set the Output N Polarity */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OCNPolarity << 8);
+
+ /* Reset the Output N State */
+ tmpccer &= CCER_CC3NE_Reset;
+
+ /* Set the Output N State */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OutputNState << 8);
+
+ /* Reset the Ouput Compare and Output Compare N IDLE State */
+ tmpcr2 &= CR2_OIS3_Reset;
+ tmpcr2 &= CR2_OIS3N_Reset;
+
+ /* Set the Output Idle state */
+ tmpcr2 |= (u16)(TIM_OCInitStruct->TIM_OCIdleState << 4);
+
+ /* Set the Output N Idle state */
+ tmpcr2 |= (u16)(TIM_OCInitStruct->TIM_OCNIdleState << 4);
+ }
+
+ /* Write to TIMx CR2 */
+ TIMx->CR2 = tmpcr2;
+
+ /* Write to TIMx CCMR2 */
+ TIMx->CCMR2 = tmpccmrx;
+
+ /* Write to TIMx CCER */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC4Init
+* Description : Initializes the TIMx Channel4 according to the specified
+* parameters in the TIM_OCInitStruct.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure
+* that contains the configuration information for the specified
+* TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+ u16 tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+ assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));
+
+ /* Disable the Channel 2: Reset the CC4E Bit */
+ TIMx->CCER &= CCER_CC4E_Reset;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = TIMx->CCER;
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = TIMx->CR2;
+
+ /* Get the TIMx CCMR2 register value */
+ tmpccmrx = TIMx->CCMR2;
+
+ /* Reset the Output Compare Mode Bits */
+ tmpccmrx &= CCMR_OC24M_Mask;
+
+ /* Select the Output Compare Mode */
+ tmpccmrx |= (u16)(TIM_OCInitStruct->TIM_OCMode << 8);
+
+ /* Reset the Output Polarity level */
+ tmpccer &= CCER_CC4P_Reset;
+
+ /* Set the Output Compare Polarity */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OCPolarity << 12);
+
+ /* Set the Output State */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OutputState << 12);
+
+ /* Set the Capture Compare Register value */
+ TIMx->CCR4 = TIM_OCInitStruct->TIM_Pulse;
+
+ if((*(u32*)&TIMx == TIM1_BASE) || (*(u32*)&TIMx == TIM8_BASE))
+ {
+ assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+
+ /* Reset the Ouput Compare IDLE State */
+ tmpcr2 &= CR2_OIS4_Reset;
+
+ /* Set the Output Idle state */
+ tmpcr2 |= (u16)(TIM_OCInitStruct->TIM_OCIdleState << 6);
+ }
+
+ /* Write to TIMx CR2 */
+ TIMx->CR2 = tmpcr2;
+
+ /* Write to TIMx CCMR2 */
+ TIMx->CCMR2 = tmpccmrx;
+
+ /* Write to TIMx CCER */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ICInit
+* Description : Initializes the TIM peripheral according to the specified
+* parameters in the TIM_ICInitStruct.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure
+* that contains the configuration information for the specified
+* TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_CHANNEL(TIM_ICInitStruct->TIM_Channel));
+ assert_param(IS_TIM_IC_POLARITY(TIM_ICInitStruct->TIM_ICPolarity));
+ assert_param(IS_TIM_IC_SELECTION(TIM_ICInitStruct->TIM_ICSelection));
+ assert_param(IS_TIM_IC_PRESCALER(TIM_ICInitStruct->TIM_ICPrescaler));
+ assert_param(IS_TIM_IC_FILTER(TIM_ICInitStruct->TIM_ICFilter));
+
+ if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1)
+ {
+ /* TI1 Configuration */
+ TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity,
+ TIM_ICInitStruct->TIM_ICSelection,
+ TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+ }
+ else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_2)
+ {
+ /* TI2 Configuration */
+ TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity,
+ TIM_ICInitStruct->TIM_ICSelection,
+ TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+ }
+ else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_3)
+ {
+ /* TI3 Configuration */
+ TI3_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity,
+ TIM_ICInitStruct->TIM_ICSelection,
+ TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC3Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+ }
+ else
+ {
+ /* TI4 Configuration */
+ TI4_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity,
+ TIM_ICInitStruct->TIM_ICSelection,
+ TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC4Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_PWMIConfig
+* Description : Configures the TIM peripheral according to the specified
+* parameters in the TIM_ICInitStruct to measure an external PWM
+* signal.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure
+* that contains the configuration information for the specified
+* TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct)
+{
+ u16 icoppositepolarity = TIM_ICPolarity_Rising;
+ u16 icoppositeselection = TIM_ICSelection_DirectTI;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Select the Opposite Input Polarity */
+ if (TIM_ICInitStruct->TIM_ICPolarity == TIM_ICPolarity_Rising)
+ {
+ icoppositepolarity = TIM_ICPolarity_Falling;
+ }
+ else
+ {
+ icoppositepolarity = TIM_ICPolarity_Rising;
+ }
+
+ /* Select the Opposite Input */
+ if (TIM_ICInitStruct->TIM_ICSelection == TIM_ICSelection_DirectTI)
+ {
+ icoppositeselection = TIM_ICSelection_IndirectTI;
+ }
+ else
+ {
+ icoppositeselection = TIM_ICSelection_DirectTI;
+ }
+
+ if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1)
+ {
+ /* TI1 Configuration */
+ TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection,
+ TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+
+ /* TI2 Configuration */
+ TI2_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+ }
+ else
+ {
+ /* TI2 Configuration */
+ TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection,
+ TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+
+ /* TI1 Configuration */
+ TI1_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_BDTRConfig
+* Description : Configures the: Break feature, dead time, Lock level, the OSSI,
+* the OSSR State and the AOE(automatic output enable).
+* Input :- TIMx: where x can be 1 or 8 to select the TIM
+* - TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef
+* structure that contains the BDTR Register configuration
+* information for the TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_TIM_OSSR_STATE(TIM_BDTRInitStruct->TIM_OSSRState));
+ assert_param(IS_TIM_OSSI_STATE(TIM_BDTRInitStruct->TIM_OSSIState));
+ assert_param(IS_TIM_LOCK_LEVEL(TIM_BDTRInitStruct->TIM_LOCKLevel));
+ assert_param(IS_TIM_BREAK_STATE(TIM_BDTRInitStruct->TIM_Break));
+ assert_param(IS_TIM_BREAK_POLARITY(TIM_BDTRInitStruct->TIM_BreakPolarity));
+ assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(TIM_BDTRInitStruct->TIM_AutomaticOutput));
+
+ /* Set the Lock level, the Break enable Bit and the Ploarity, the OSSR State,
+ the OSSI State, the dead time value and the Automatic Output Enable Bit */
+
+ TIMx->BDTR = (u32)TIM_BDTRInitStruct->TIM_OSSRState | TIM_BDTRInitStruct->TIM_OSSIState |
+ TIM_BDTRInitStruct->TIM_LOCKLevel | TIM_BDTRInitStruct->TIM_DeadTime |
+ TIM_BDTRInitStruct->TIM_Break | TIM_BDTRInitStruct->TIM_BreakPolarity |
+ TIM_BDTRInitStruct->TIM_AutomaticOutput;
+
+}
+
+/*******************************************************************************
+* Function Name : TIM_TimeBaseStructInit
+* Description : Fills each TIM_TimeBaseInitStruct member with its default value.
+* Input : - TIM_TimeBaseInitStruct : pointer to a TIM_TimeBaseInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct)
+{
+ /* Set the default configuration */
+ TIM_TimeBaseInitStruct->TIM_Period = 0xFFFF;
+ TIM_TimeBaseInitStruct->TIM_Prescaler = 0x0000;
+ TIM_TimeBaseInitStruct->TIM_ClockDivision = TIM_CKD_DIV1;
+ TIM_TimeBaseInitStruct->TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseInitStruct->TIM_RepetitionCounter = 0x0000;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OCStructInit
+* Description : Fills each TIM_OCInitStruct member with its default value.
+* Input : - TIM_OCInitStruct : pointer to a TIM_OCInitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+ /* Set the default configuration */
+ TIM_OCInitStruct->TIM_OCMode = TIM_OCMode_Timing;
+ TIM_OCInitStruct->TIM_OutputState = TIM_OutputState_Disable;
+ TIM_OCInitStruct->TIM_OutputNState = TIM_OutputNState_Disable;
+ TIM_OCInitStruct->TIM_Pulse = 0x0000;
+ TIM_OCInitStruct->TIM_OCPolarity = TIM_OCPolarity_High;
+ TIM_OCInitStruct->TIM_OCNPolarity = TIM_OCPolarity_High;
+ TIM_OCInitStruct->TIM_OCIdleState = TIM_OCIdleState_Reset;
+ TIM_OCInitStruct->TIM_OCNIdleState = TIM_OCNIdleState_Reset;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ICStructInit
+* Description : Fills each TIM_ICInitStruct member with its default value.
+* Input : - TIM_ICInitStruct : pointer to a TIM_ICInitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct)
+{
+ /* Set the default configuration */
+ TIM_ICInitStruct->TIM_Channel = TIM_Channel_1;
+ TIM_ICInitStruct->TIM_ICPolarity = TIM_ICPolarity_Rising;
+ TIM_ICInitStruct->TIM_ICSelection = TIM_ICSelection_DirectTI;
+ TIM_ICInitStruct->TIM_ICPrescaler = TIM_ICPSC_DIV1;
+ TIM_ICInitStruct->TIM_ICFilter = 0x00;
+}
+
+/*******************************************************************************
+* Function Name : TIM_BDTRStructInit
+* Description : Fills each TIM_BDTRInitStruct member with its default value.
+* Input : - TIM_BDTRInitStruct : pointer to a TIM_BDTRInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct)
+{
+ /* Set the default configuration */
+ TIM_BDTRInitStruct->TIM_OSSRState = TIM_OSSRState_Disable;
+ TIM_BDTRInitStruct->TIM_OSSIState = TIM_OSSIState_Disable;
+ TIM_BDTRInitStruct->TIM_LOCKLevel = TIM_LOCKLevel_OFF;
+ TIM_BDTRInitStruct->TIM_DeadTime = 0x00;
+ TIM_BDTRInitStruct->TIM_Break = TIM_Break_Disable;
+ TIM_BDTRInitStruct->TIM_BreakPolarity = TIM_BreakPolarity_Low;
+ TIM_BDTRInitStruct->TIM_AutomaticOutput = TIM_AutomaticOutput_Disable;
+}
+
+/*******************************************************************************
+* Function Name : TIM_Cmd
+* Description : Enables or disables the specified TIM peripheral.
+* Input : - TIMx: where x can be 1 to 8 to select the TIMx peripheral.
+* - NewState: new state of the TIMx peripheral.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the TIM Counter */
+ TIMx->CR1 |= CR1_CEN_Set;
+ }
+ else
+ {
+ /* Disable the TIM Counter */
+ TIMx->CR1 &= CR1_CEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_CtrlPWMOutputs
+* Description : Enables or disables the TIM peripheral Main Outputs.
+* Input :- TIMx: where x can be 1 or 8 to select the TIMx peripheral.
+* - NewState: new state of the TIM peripheral Main Outputs.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the TIM Main Output */
+ TIMx->BDTR |= BDTR_MOE_Set;
+ }
+ else
+ {
+ /* Disable the TIM Main Output */
+ TIMx->BDTR &= BDTR_MOE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_ITConfig
+* Description : Enables or disables the specified TIM interrupts.
+* Input : - TIMx: where x can be 1 to 8 to select the TIMx peripheral.
+* - TIM_IT: specifies the TIM interrupts sources to be enabled
+* or disabled.
+* This parameter can be any combination of the following values:
+* - TIM_IT_Update: TIM update Interrupt source
+* - TIM_IT_CC1: TIM Capture Compare 1 Interrupt source
+* - TIM_IT_CC2: TIM Capture Compare 2 Interrupt source
+* - TIM_IT_CC3: TIM Capture Compare 3 Interrupt source
+* - TIM_IT_CC4: TIM Capture Compare 4 Interrupt source
+* - TIM_IT_COM: TIM Commutation Interrupt source
+* - TIM_IT_Trigger: TIM Trigger Interrupt source
+* - TIM_IT_Break: TIM Break Interrupt source
+* - NewState: new state of the TIM interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ITConfig(TIM_TypeDef* TIMx, u16 TIM_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_IT(TIM_IT));
+ assert_param(IS_TIM_PERIPH_IT((TIMx), (TIM_IT)));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the Interrupt sources */
+ TIMx->DIER |= TIM_IT;
+ }
+ else
+ {
+ /* Disable the Interrupt sources */
+ TIMx->DIER &= (u16)~TIM_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_GenerateEvent
+* Description : Configures the TIMx event to be generate by software.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_EventSource: specifies the event source.
+* This parameter can be one or more of the following values:
+* - TIM_EventSource_Update: Timer update Event source
+* - TIM_EventSource_CC1: Timer Capture Compare 1 Event source
+* - TIM_EventSource_CC2: Timer Capture Compare 2 Event source
+* - TIM_EventSource_CC3: Timer Capture Compare 3 Event source
+* - TIM_EventSource_CC4: Timer Capture Compare 4 Event source
+* - TIM_EventSource_Trigger: Timer Trigger Event source
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_GenerateEvent(TIM_TypeDef* TIMx, u16 TIM_EventSource)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_EVENT_SOURCE(TIM_EventSource));
+ assert_param(IS_TIM_PERIPH_EVENT((TIMx), (TIM_EventSource)));
+
+ /* Set the event sources */
+ TIMx->EGR = TIM_EventSource;
+}
+
+/*******************************************************************************
+* Function Name : TIM_DMAConfig
+* Description : Configures the TIMx’s DMA interface.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_DMABase: DMA Base address.
+* This parameter can be one of the following values:
+* - TIM_DMABase_CR, TIM_DMABase_CR2, TIM_DMABase_SMCR,
+* TIM_DMABase_DIER, TIM1_DMABase_SR, TIM_DMABase_EGR,
+* TIM_DMABase_CCMR1, TIM_DMABase_CCMR2, TIM_DMABase_CCER,
+* TIM_DMABase_CNT, TIM_DMABase_PSC, TIM_DMABase_ARR,
+* TIM_DMABase_RCR, TIM_DMABase_CCR1, TIM_DMABase_CCR2,
+* TIM_DMABase_CCR3, TIM_DMABase_CCR4, TIM_DMABase_BDTR,
+* TIM_DMABase_DCR.
+* - TIM_DMABurstLength: DMA Burst length.
+* This parameter can be one value between:
+* TIM_DMABurstLength_1Byte and TIM_DMABurstLength_18Bytes.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_DMAConfig(TIM_TypeDef* TIMx, u16 TIM_DMABase, u16 TIM_DMABurstLength)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_DMA_BASE(TIM_DMABase));
+ assert_param(IS_TIM_DMA_LENGTH(TIM_DMABurstLength));
+
+ /* Set the DMA Base and the DMA Burst Length */
+ TIMx->DCR = TIM_DMABase | TIM_DMABurstLength;
+}
+
+/*******************************************************************************
+* Function Name : TIM_DMACmd
+* Description : Enables or disables the TIMx’s DMA Requests.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_DMASources: specifies the DMA Request sources.
+* This parameter can be any combination of the following values:
+* - TIM_DMA_Update: TIM update Interrupt source
+* - TIM_DMA_CC1: TIM Capture Compare 1 DMA source
+* - TIM_DMA_CC2: TIM Capture Compare 2 DMA source
+* - TIM_DMA_CC3: TIM Capture Compare 3 DMA source
+* - TIM_DMA_CC4: TIM Capture Compare 4 DMA source
+* - TIM_DMA_COM: TIM Commutation DMA source
+* - TIM_DMA_Trigger: TIM Trigger DMA source
+* - NewState: new state of the DMA Request sources.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_DMACmd(TIM_TypeDef* TIMx, u16 TIM_DMASource, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_DMA_SOURCE(TIM_DMASource));
+ assert_param(IS_TIM_PERIPH_DMA(TIMx, TIM_DMASource));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the DMA sources */
+ TIMx->DIER |= TIM_DMASource;
+ }
+ else
+ {
+ /* Disable the DMA sources */
+ TIMx->DIER &= (u16)~TIM_DMASource;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_InternalClockConfig
+* Description : Configures the TIMx interrnal Clock
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_InternalClockConfig(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Disable slave mode to clock the prescaler directly with the internal clock */
+ TIMx->SMCR &= SMCR_SMS_Mask;
+}
+/*******************************************************************************
+* Function Name : TIM_ITRxExternalClockConfig
+* Description : Configures the TIMx Internal Trigger as External Clock
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ITRSource: Trigger source.
+* This parameter can be one of the following values:
+* - TIM_TS_ITR0: Internal Trigger 0
+* - TIM_TS_ITR1: Internal Trigger 1
+* - TIM_TS_ITR2: Internal Trigger 2
+* - TIM_TS_ITR3: Internal Trigger 3
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, u16 TIM_InputTriggerSource)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_INTERNAL_TRIGGER_SELECTION(TIM_InputTriggerSource));
+
+ /* Select the Internal Trigger */
+ TIM_SelectInputTrigger(TIMx, TIM_InputTriggerSource);
+
+ /* Select the External clock mode1 */
+ TIMx->SMCR |= TIM_SlaveMode_External1;
+}
+/*******************************************************************************
+* Function Name : TIM_TIxExternalClockConfig
+* Description : Configures the TIMx Trigger as External Clock
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_TIxExternalCLKSource: Trigger source.
+* This parameter can be one of the following values:
+* - TIM_TIxExternalCLK1Source_TI1ED: TI1 Edge Detector
+* - TIM_TIxExternalCLK1Source_TI1: Filtered Timer Input 1
+* - TIM_TIxExternalCLK1Source_TI2: Filtered Timer Input 2
+* - TIM_ICPolarity: specifies the TIx Polarity.
+* This parameter can be:
+* - TIM_ICPolarity_Rising
+* - TIM_ICPolarity_Falling
+* - ICFilter : specifies the filter value.
+* This parameter must be a value between 0x0 and 0xF.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, u16 TIM_TIxExternalCLKSource,
+ u16 TIM_ICPolarity, u16 ICFilter)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_TIXCLK_SOURCE(TIM_TIxExternalCLKSource));
+ assert_param(IS_TIM_IC_POLARITY(TIM_ICPolarity));
+ assert_param(IS_TIM_IC_FILTER(ICFilter));
+
+ /* Configure the Timer Input Clock Source */
+ if (TIM_TIxExternalCLKSource == TIM_TIxExternalCLK1Source_TI2)
+ {
+ TI2_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter);
+ }
+ else
+ {
+ TI1_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter);
+ }
+
+ /* Select the Trigger source */
+ TIM_SelectInputTrigger(TIMx, TIM_TIxExternalCLKSource);
+
+ /* Select the External clock mode1 */
+ TIMx->SMCR |= TIM_SlaveMode_External1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ETRClockMode1Config
+* Description : Configures the External clock Mode1
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ExtTRGPrescaler: The external Trigger Prescaler.
+* It can be one of the following values:
+* - TIM_ExtTRGPSC_OFF
+* - TIM_ExtTRGPSC_DIV2
+* - TIM_ExtTRGPSC_DIV4
+* - TIM_ExtTRGPSC_DIV8.
+* - TIM_ExtTRGPolarity: The external Trigger Polarity.
+* It can be one of the following values:
+* - TIM_ExtTRGPolarity_Inverted
+* - TIM_ExtTRGPolarity_NonInverted
+* - ExtTRGFilter: External Trigger Filter.
+* This parameter must be a value between 0x00 and 0x0F
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, u16 TIM_ExtTRGPrescaler, u16 TIM_ExtTRGPolarity,
+ u16 ExtTRGFilter)
+{
+ u16 tmpsmcr = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler));
+ assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity));
+ assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter));
+
+ /* Configure the ETR Clock source */
+ TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter);
+
+ /* Get the TIMx SMCR register value */
+ tmpsmcr = TIMx->SMCR;
+
+ /* Reset the SMS Bits */
+ tmpsmcr &= SMCR_SMS_Mask;
+ /* Select the External clock mode1 */
+ tmpsmcr |= TIM_SlaveMode_External1;
+
+ /* Select the Trigger selection : ETRF */
+ tmpsmcr &= SMCR_TS_Mask;
+ tmpsmcr |= TIM_TS_ETRF;
+
+ /* Write to TIMx SMCR */
+ TIMx->SMCR = tmpsmcr;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ETRClockMode2Config
+* Description : Configures the External clock Mode2
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ExtTRGPrescaler: The external Trigger Prescaler.
+* It can be one of the following values:
+* - TIM_ExtTRGPSC_OFF
+* - TIM_ExtTRGPSC_DIV2
+* - TIM_ExtTRGPSC_DIV4
+* - TIM_ExtTRGPSC_DIV8
+* - TIM_ExtTRGPolarity: The external Trigger Polarity.
+* It can be one of the following values:
+* - TIM_ExtTRGPolarity_Inverted
+* - TIM_ExtTRGPolarity_NonInverted
+* - ExtTRGFilter: External Trigger Filter.
+* This parameter must be a value between 0x00 and 0x0F
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, u16 TIM_ExtTRGPrescaler,
+ u16 TIM_ExtTRGPolarity, u16 ExtTRGFilter)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler));
+ assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity));
+ assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter));
+
+ /* Configure the ETR Clock source */
+ TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter);
+
+ /* Enable the External clock mode2 */
+ TIMx->SMCR |= SMCR_ECE_Set;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ETRConfig
+* Description : Configures the TIMx External Trigger (ETR).
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ExtTRGPrescaler: The external Trigger Prescaler.
+* This parameter can be one of the following values:
+* - TIM_ExtTRGPSC_OFF
+* - TIM_ExtTRGPSC_DIV2
+* - TIM_ExtTRGPSC_DIV4
+* - TIM_ExtTRGPSC_DIV8
+* - TIM_ExtTRGPolarity: The external Trigger Polarity.
+* This parameter can be one of the following values:
+* - TIM_ExtTRGPolarity_Inverted
+* - TIM_ExtTRGPolarity_NonInverted
+* - ExtTRGFilter: External Trigger Filter.
+* This parameter must be a value between 0x00 and 0x0F.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ETRConfig(TIM_TypeDef* TIMx, u16 TIM_ExtTRGPrescaler, u16 TIM_ExtTRGPolarity,
+ u16 ExtTRGFilter)
+{
+ u16 tmpsmcr = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler));
+ assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity));
+ assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter));
+
+ tmpsmcr = TIMx->SMCR;
+
+ /* Reset the ETR Bits */
+ tmpsmcr &= SMCR_ETR_Mask;
+
+ /* Set the Prescaler, the Filter value and the Polarity */
+ tmpsmcr |= TIM_ExtTRGPrescaler | TIM_ExtTRGPolarity | (u16)(ExtTRGFilter << 8);
+
+ /* Write to TIMx SMCR */
+ TIMx->SMCR = tmpsmcr;
+}
+
+/*******************************************************************************
+* Function Name : TIM_PrescalerConfig
+* Description : Configures the TIMx Prescaler.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - Prescaler: specifies the Prescaler Register value
+* - TIM_PSCReloadMode: specifies the TIM Prescaler Reload mode
+* This parameter can be one of the following values:
+* - TIM_PSCReloadMode_Update: The Prescaler is loaded at
+* the update event.
+* - TIM_PSCReloadMode_Immediate: The Prescaler is loaded
+* immediatly.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_PrescalerConfig(TIM_TypeDef* TIMx, u16 Prescaler, u16 TIM_PSCReloadMode)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_PRESCALER_RELOAD(TIM_PSCReloadMode));
+
+ /* Set the Prescaler value */
+ TIMx->PSC = Prescaler;
+
+ /* Set or reset the UG Bit */
+ TIMx->EGR = TIM_PSCReloadMode;
+}
+
+/*******************************************************************************
+* Function Name : TIM_CounterModeConfig
+* Description : Specifies the TIMx Counter Mode to be used.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_CounterMode: specifies the Counter Mode to be used
+* This parameter can be one of the following values:
+* - TIM_CounterMode_Up: TIM Up Counting Mode
+* - TIM_CounterMode_Down: TIM Down Counting Mode
+* - TIM_CounterMode_CenterAligned1: TIM Center Aligned Mode1
+* - TIM_CounterMode_CenterAligned2: TIM Center Aligned Mode2
+* - TIM_CounterMode_CenterAligned3: TIM Center Aligned Mode3
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_CounterModeConfig(TIM_TypeDef* TIMx, u16 TIM_CounterMode)
+{
+ u16 tmpcr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_COUNTER_MODE(TIM_CounterMode));
+
+ tmpcr1 = TIMx->CR1;
+
+ /* Reset the CMS and DIR Bits */
+ tmpcr1 &= CR1_CounterMode_Mask;
+
+ /* Set the Counter Mode */
+ tmpcr1 |= TIM_CounterMode;
+
+ /* Write to TIMx CR1 register */
+ TIMx->CR1 = tmpcr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectInputTrigger
+* Description : Selects the Input Trigger source
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_InputTriggerSource: The Input Trigger source.
+* This parameter can be one of the following values:
+* - TIM_TS_ITR0: Internal Trigger 0
+* - TIM_TS_ITR1: Internal Trigger 1
+* - TIM_TS_ITR2: Internal Trigger 2
+* - TIM_TS_ITR3: Internal Trigger 3
+* - TIM_TS_TI1F_ED: TI1 Edge Detector
+* - TIM_TS_TI1FP1: Filtered Timer Input 1
+* - TIM_TS_TI2FP2: Filtered Timer Input 2
+* - TIM_TS_ETRF: External Trigger input
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, u16 TIM_InputTriggerSource)
+{
+ u16 tmpsmcr = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_TRIGGER_SELECTION(TIM_InputTriggerSource));
+
+ /* Get the TIMx SMCR register value */
+ tmpsmcr = TIMx->SMCR;
+
+ /* Reset the TS Bits */
+ tmpsmcr &= SMCR_TS_Mask;
+
+ /* Set the Input Trigger source */
+ tmpsmcr |= TIM_InputTriggerSource;
+
+ /* Write to TIMx SMCR */
+ TIMx->SMCR = tmpsmcr;
+}
+
+/*******************************************************************************
+* Function Name : TIM_EncoderInterfaceConfig
+* Description : Configures the TIMx Encoder Interface.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_EncoderMode: specifies the TIMx Encoder Mode.
+* This parameter can be one of the following values:
+* - TIM_EncoderMode_TI1: Counter counts on TI1FP1 edge
+* depending on TI2FP2 level.
+* - TIM_EncoderMode_TI2: Counter counts on TI2FP2 edge
+* depending on TI1FP1 level.
+* - TIM_EncoderMode_TI12: Counter counts on both TI1FP1 and
+* TI2FP2 edges depending on the level of the other input.
+* - TIM_IC1Polarity: specifies the IC1 Polarity
+* This parmeter can be one of the following values:
+* - TIM_ICPolarity_Falling: IC Falling edge.
+* - TIM_ICPolarity_Rising: IC Rising edge.
+* - TIM_IC2Polarity: specifies the IC2 Polarity
+* This parmeter can be one of the following values:
+* - TIM_ICPolarity_Falling: IC Falling edge.
+* - TIM_ICPolarity_Rising: IC Rising edge.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, u16 TIM_EncoderMode,
+ u16 TIM_IC1Polarity, u16 TIM_IC2Polarity)
+{
+ u16 tmpsmcr = 0;
+ u16 tmpccmr1 = 0;
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_ENCODER_MODE(TIM_EncoderMode));
+ assert_param(IS_TIM_IC_POLARITY(TIM_IC1Polarity));
+ assert_param(IS_TIM_IC_POLARITY(TIM_IC2Polarity));
+
+ /* Get the TIMx SMCR register value */
+ tmpsmcr = TIMx->SMCR;
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = TIMx->CCER;
+
+ /* Set the encoder Mode */
+ tmpsmcr &= SMCR_SMS_Mask;
+ tmpsmcr |= TIM_EncoderMode;
+
+ /* Select the Capture Compare 1 and the Capture Compare 2 as input */
+ tmpccmr1 &= CCMR_CC13S_Mask & CCMR_CC24S_Mask;
+ tmpccmr1 |= CCMR_TI13Direct_Set | CCMR_TI24Direct_Set;
+
+ /* Set the TI1 and the TI2 Polarities */
+ tmpccer &= CCER_CC1P_Reset & CCER_CC2P_Reset;
+ tmpccer |= (TIM_IC1Polarity | (u16)(TIM_IC2Polarity << 4));
+
+ /* Write to TIMx SMCR */
+ TIMx->SMCR = tmpsmcr;
+
+ /* Write to TIMx CCMR1 */
+ TIMx->CCMR1 = tmpccmr1;
+
+ /* Write to TIMx CCER */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ForcedOC1Config
+* Description : Forces the TIMx output 1 waveform to active or inactive level.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ForcedAction: specifies the forced Action to be set to
+* the output waveform.
+* This parameter can be one of the following values:
+* - TIM_ForcedAction_Active: Force active level on OC1REF
+* - TIM_ForcedAction_InActive: Force inactive level on
+* OC1REF.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC1M Bits */
+ tmpccmr1 &= CCMR_OC13M_Mask;
+
+ /* Configure The Forced output Mode */
+ tmpccmr1 |= TIM_ForcedAction;
+
+ /* Write to TIMx CCMR1 register */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ForcedOC2Config
+* Description : Forces the TIMx output 2 waveform to active or inactive level.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ForcedAction: specifies the forced Action to be set to
+* the output waveform.
+* This parameter can be one of the following values:
+* - TIM_ForcedAction_Active: Force active level on OC2REF
+* - TIM_ForcedAction_InActive: Force inactive level on
+* OC2REF.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC2M Bits */
+ tmpccmr1 &= CCMR_OC24M_Mask;
+
+ /* Configure The Forced output Mode */
+ tmpccmr1 |= (u16)(TIM_ForcedAction << 8);
+
+ /* Write to TIMx CCMR1 register */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ForcedOC3Config
+* Description : Forces the TIMx output 3 waveform to active or inactive level.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ForcedAction: specifies the forced Action to be set to
+* the output waveform.
+* This parameter can be one of the following values:
+* - TIM_ForcedAction_Active: Force active level on OC3REF
+* - TIM_ForcedAction_InActive: Force inactive level on
+* OC3REF.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC1M Bits */
+ tmpccmr2 &= CCMR_OC13M_Mask;
+
+ /* Configure The Forced output Mode */
+ tmpccmr2 |= TIM_ForcedAction;
+
+ /* Write to TIMx CCMR2 register */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ForcedOC4Config
+* Description : Forces the TIMx output 4 waveform to active or inactive level.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ForcedAction: specifies the forced Action to be set to
+* the output waveform.
+* This parameter can be one of the following values:
+* - TIM_ForcedAction_Active: Force active level on OC4REF
+* - TIM_ForcedAction_InActive: Force inactive level on
+* OC4REF.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC2M Bits */
+ tmpccmr2 &= CCMR_OC24M_Mask;
+
+ /* Configure The Forced output Mode */
+ tmpccmr2 |= (u16)(TIM_ForcedAction << 8);
+
+ /* Write to TIMx CCMR2 register */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ARRPreloadConfig
+* Description : Enables or disables TIMx peripheral Preload register on ARR.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - NewState: new state of the TIMx peripheral Preload register
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Set the ARR Preload Bit */
+ TIMx->CR1 |= CR1_ARPE_Set;
+ }
+ else
+ {
+ /* Reset the ARR Preload Bit */
+ TIMx->CR1 &= CR1_ARPE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectCOM
+* Description : Selects the TIM peripheral Commutation event.
+* Input :- TIMx: where x can be 1 or 8 to select the TIMx peripheral
+* - NewState: new state of the Commutation event.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Set the COM Bit */
+ TIMx->CR2 |= CR2_CCUS_Set;
+ }
+ else
+ {
+ /* Reset the COM Bit */
+ TIMx->CR2 &= CR2_CCUS_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectCCDMA
+* Description : Selects the TIMx peripheral Capture Compare DMA source.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - NewState: new state of the Capture Compare DMA source
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Set the CCDS Bit */
+ TIMx->CR2 |= CR2_CCDS_Set;
+ }
+ else
+ {
+ /* Reset the CCDS Bit */
+ TIMx->CR2 &= CR2_CCDS_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_CCPreloadControl
+* Description : Sets or Resets the TIM peripheral Capture Compare Preload
+* Control bit.
+* Input :- TIMx: where x can be 1 or 8 to select the TIMx peripheral
+* - NewState: new state of the Capture Compare Preload Control bit
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Set the CCPC Bit */
+ TIMx->CR2 |= CR2_CCPC_Set;
+ }
+ else
+ {
+ /* Reset the CCPC Bit */
+ TIMx->CR2 &= CR2_CCPC_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC1PreloadConfig
+* Description : Enables or disables the TIMx peripheral Preload register on CCR1.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPreload: new state of the TIMx peripheral Preload
+* register
+* This parameter can be one of the following values:
+* - TIM_OCPreload_Enable
+* - TIM_OCPreload_Disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC1PE Bit */
+ tmpccmr1 &= CCMR_OC13PE_Reset;
+
+ /* Enable or Disable the Output Compare Preload feature */
+ tmpccmr1 |= TIM_OCPreload;
+
+ /* Write to TIMx CCMR1 register */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC2PreloadConfig
+* Description : Enables or disables the TIMx peripheral Preload register on CCR2.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPreload: new state of the TIMx peripheral Preload
+* register
+* This parameter can be one of the following values:
+* - TIM_OCPreload_Enable
+* - TIM_OCPreload_Disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC2PE Bit */
+ tmpccmr1 &= CCMR_OC24PE_Reset;
+
+ /* Enable or Disable the Output Compare Preload feature */
+ tmpccmr1 |= (u16)(TIM_OCPreload << 8);
+
+ /* Write to TIMx CCMR1 register */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC3PreloadConfig
+* Description : Enables or disables the TIMx peripheral Preload register on CCR3.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPreload: new state of the TIMx peripheral Preload
+* register
+* This parameter can be one of the following values:
+* - TIM_OCPreload_Enable
+* - TIM_OCPreload_Disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC3PE Bit */
+ tmpccmr2 &= CCMR_OC13PE_Reset;
+
+ /* Enable or Disable the Output Compare Preload feature */
+ tmpccmr2 |= TIM_OCPreload;
+
+ /* Write to TIMx CCMR2 register */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC4PreloadConfig
+* Description : Enables or disables the TIMx peripheral Preload register on CCR4.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPreload: new state of the TIMx peripheral Preload
+* register
+* This parameter can be one of the following values:
+* - TIM_OCPreload_Enable
+* - TIM_OCPreload_Disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC4PE Bit */
+ tmpccmr2 &= CCMR_OC24PE_Reset;
+
+ /* Enable or Disable the Output Compare Preload feature */
+ tmpccmr2 |= (u16)(TIM_OCPreload << 8);
+
+ /* Write to TIMx CCMR2 register */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC1FastConfig
+* Description : Configures the TIMx Output Compare 1 Fast feature.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCFast_Enable: TIM output compare fast enable
+* - TIM_OCFast_Disable: TIM output compare fast disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC1FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC1FE Bit */
+ tmpccmr1 &= CCMR_OC13FE_Reset;
+
+ /* Enable or Disable the Output Compare Fast Bit */
+ tmpccmr1 |= TIM_OCFast;
+
+ /* Write to TIMx CCMR1 */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC2FastConfig
+* Description : Configures the TIMx Output Compare 2 Fast feature.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCFast_Enable: TIM output compare fast enable
+* - TIM_OCFast_Disable: TIM output compare fast disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC2FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC2FE Bit */
+ tmpccmr1 &= CCMR_OC24FE_Reset;
+
+ /* Enable or Disable the Output Compare Fast Bit */
+ tmpccmr1 |= (u16)(TIM_OCFast << 8);
+
+ /* Write to TIMx CCMR1 */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC3FastConfig
+* Description : Configures the TIMx Output Compare 3 Fast feature.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCFast_Enable: TIM output compare fast enable
+* - TIM_OCFast_Disable: TIM output compare fast disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC3FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+
+ /* Get the TIMx CCMR2 register value */
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC3FE Bit */
+ tmpccmr2 &= CCMR_OC13FE_Reset;
+
+ /* Enable or Disable the Output Compare Fast Bit */
+ tmpccmr2 |= TIM_OCFast;
+
+ /* Write to TIMx CCMR2 */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC4FastConfig
+* Description : Configures the TIMx Output Compare 4 Fast feature.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCFast_Enable: TIM output compare fast enable
+* - TIM_OCFast_Disable: TIM output compare fast disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC4FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+
+ /* Get the TIMx CCMR2 register value */
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC4FE Bit */
+ tmpccmr2 &= CCMR_OC24FE_Reset;
+
+ /* Enable or Disable the Output Compare Fast Bit */
+ tmpccmr2 |= (u16)(TIM_OCFast << 8);
+
+ /* Write to TIMx CCMR2 */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ClearOC1Ref
+* Description : Clears or safeguards the OCREF1 signal on an external event
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCClear_Enable: TIM Output clear enable
+* - TIM_OCClear_Disable: TIM Output clear disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC1CE Bit */
+ tmpccmr1 &= CCMR_OC13CE_Reset;
+
+ /* Enable or Disable the Output Compare Clear Bit */
+ tmpccmr1 |= TIM_OCClear;
+
+ /* Write to TIMx CCMR1 register */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ClearOC2Ref
+* Description : Clears or safeguards the OCREF2 signal on an external event
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCClear_Enable: TIM Output clear enable
+* - TIM_OCClear_Disable: TIM Output clear disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC2CE Bit */
+ tmpccmr1 &= CCMR_OC24CE_Reset;
+
+ /* Enable or Disable the Output Compare Clear Bit */
+ tmpccmr1 |= (u16)(TIM_OCClear << 8);
+
+ /* Write to TIMx CCMR1 register */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ClearOC3Ref
+* Description : Clears or safeguards the OCREF3 signal on an external event
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCClear_Enable: TIM Output clear enable
+* - TIM_OCClear_Disable: TIM Output clear disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC3CE Bit */
+ tmpccmr2 &= CCMR_OC13CE_Reset;
+
+ /* Enable or Disable the Output Compare Clear Bit */
+ tmpccmr2 |= TIM_OCClear;
+
+ /* Write to TIMx CCMR2 register */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ClearOC4Ref
+* Description : Clears or safeguards the OCREF4 signal on an external event
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCClear_Enable: TIM Output clear enable
+* - TIM_OCClear_Disable: TIM Output clear disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC4CE Bit */
+ tmpccmr2 &= CCMR_OC24CE_Reset;
+
+ /* Enable or Disable the Output Compare Clear Bit */
+ tmpccmr2 |= (u16)(TIM_OCClear << 8);
+
+ /* Write to TIMx CCMR2 register */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC1PolarityConfig
+* Description : Configures the TIMx channel 1 polarity.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPolarity: specifies the OC1 Polarity
+* This parmeter can be one of the following values:
+* - TIM_OCPolarity_High: Output Compare active high
+* - TIM_OCPolarity_Low: Output Compare active low
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity)
+{
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+
+ tmpccer = TIMx->CCER;
+
+ /* Set or Reset the CC1P Bit */
+ tmpccer &= CCER_CC1P_Reset;
+ tmpccer |= TIM_OCPolarity;
+
+ /* Write to TIMx CCER register */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC1NPolarityConfig
+* Description : Configures the TIMx Channel 1N polarity.
+* Input : - TIMx: where x can be 1 or 8 to select the TIM peripheral.
+* - TIM_OCNPolarity: specifies the OC1N Polarity
+* This parmeter can be one of the following values:
+* - TIM_OCNPolarity_High: Output Compare active high
+* - TIM_OCNPolarity_Low: Output Compare active low
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCNPolarity)
+{
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity));
+
+ tmpccer = TIMx->CCER;
+
+ /* Set or Reset the CC1NP Bit */
+ tmpccer &= CCER_CC1NP_Reset;
+ tmpccer |= TIM_OCNPolarity;
+
+ /* Write to TIMx CCER register */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC2PolarityConfig
+* Description : Configures the TIMx channel 2 polarity.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPolarity: specifies the OC2 Polarity
+* This parmeter can be one of the following values:
+* - TIM_OCPolarity_High: Output Compare active high
+* - TIM_OCPolarity_Low: Output Compare active low
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity)
+{
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+
+ tmpccer = TIMx->CCER;
+
+ /* Set or Reset the CC2P Bit */
+ tmpccer &= CCER_CC2P_Reset;
+ tmpccer |= (u16)(TIM_OCPolarity << 4);
+
+ /* Write to TIMx CCER register */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC2NPolarityConfig
+* Description : Configures the TIMx Channel 2N polarity.
+* Input : - TIMx: where x can be 1 or 8 to select the TIM peripheral.
+* - TIM_OCNPolarity: specifies the OC2N Polarity
+* This parmeter can be one of the following values:
+* - TIM_OCNPolarity_High: Output Compare active high
+* - TIM_OCNPolarity_Low: Output Compare active low
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCNPolarity)
+{
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity));
+
+ tmpccer = TIMx->CCER;
+
+ /* Set or Reset the CC2NP Bit */
+ tmpccer &= CCER_CC2NP_Reset;
+ tmpccer |= (u16)(TIM_OCNPolarity << 4);
+
+ /* Write to TIMx CCER register */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC3PolarityConfig
+* Description : Configures the TIMx channel 3 polarity.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPolarity: specifies the OC3 Polarity
+* This parmeter can be one of the following values:
+* - TIM_OCPolarity_High: Output Compare active high
+* - TIM_OCPolarity_Low: Output Compare active low
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity)
+{
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+
+ tmpccer = TIMx->CCER;
+
+ /* Set or Reset the CC3P Bit */
+ tmpccer &= CCER_CC3P_Reset;
+ tmpccer |= (u16)(TIM_OCPolarity << 8);
+
+ /* Write to TIMx CCER register */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC3NPolarityConfig
+* Description : Configures the TIMx Channel 3N polarity.
+* Input : - TIMx: where x can be 1 or 8 to select the TIM peripheral.
+* - TIM_OCNPolarity: specifies the OC3N Polarity
+* This parmeter can be one of the following values:
+* - TIM_OCNPolarity_High: Output Compare active high
+* - TIM_OCNPolarity_Low: Output Compare active low
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCNPolarity)
+{
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity));
+
+ tmpccer = TIMx->CCER;
+
+ /* Set or Reset the CC3NP Bit */
+ tmpccer &= CCER_CC3NP_Reset;
+ tmpccer |= (u16)(TIM_OCNPolarity << 8);
+
+ /* Write to TIMx CCER register */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC4PolarityConfig
+* Description : Configures the TIMx channel 4 polarity.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPolarity: specifies the OC4 Polarity
+* This parmeter can be one of the following values:
+* - TIM_OCPolarity_High: Output Compare active high
+* - TIM_OCPolarity_Low: Output Compare active low
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity)
+{
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+
+ tmpccer = TIMx->CCER;
+
+ /* Set or Reset the CC4P Bit */
+ tmpccer &= CCER_CC4P_Reset;
+ tmpccer |= (u16)(TIM_OCPolarity << 12);
+
+ /* Write to TIMx CCER register */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_CCxCmd
+* Description : Enables or disables the TIM Capture Compare Channel x.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_Channel: specifies the TIM Channel
+* This parmeter can be one of the following values:
+* - TIM_Channel_1: TIM Channel 1
+* - TIM_Channel_2: TIM Channel 2
+* - TIM_Channel_3: TIM Channel 3
+* - TIM_Channel_4: TIM Channel 4
+* - TIM_CCx: specifies the TIM Channel CCxE bit new state.
+* This parameter can be: TIM_CCx_Enable or TIM_CCx_Disable.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_CCxCmd(TIM_TypeDef* TIMx, u16 TIM_Channel, u16 TIM_CCx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_CHANNEL(TIM_Channel));
+ assert_param(IS_TIM_CCX(TIM_CCx));
+
+ /* Reset the CCxE Bit */
+ TIMx->CCER &= (u16)(~((u16)(CCER_CCE_Set << TIM_Channel)));
+
+ /* Set or reset the CCxE Bit */
+ TIMx->CCER |= (u16)(TIM_CCx << TIM_Channel);
+}
+
+/*******************************************************************************
+* Function Name : TIM_CCxNCmd
+* Description : Enables or disables the TIM Capture Compare Channel xN.
+* Input :- TIMx: where x can be 1 or 8 to select the TIM peripheral.
+* - TIM_Channel: specifies the TIM Channel
+* This parmeter can be one of the following values:
+* - TIM_Channel_1: TIM Channel 1
+* - TIM_Channel_2: TIM Channel 2
+* - TIM_Channel_3: TIM Channel 3
+* - TIM_CCx: specifies the TIM Channel CCxNE bit new state.
+* This parameter can be: TIM_CCxN_Enable or TIM_CCxN_Disable.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_CCxNCmd(TIM_TypeDef* TIMx, u16 TIM_Channel, u16 TIM_CCxN)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_TIM_COMPLEMENTARY_CHANNEL(TIM_Channel));
+ assert_param(IS_TIM_CCXN(TIM_CCxN));
+
+ /* Reset the CCxNE Bit */
+ TIMx->CCER &= (u16)(~((u16)(CCER_CCNE_Set << TIM_Channel)));
+
+ /* Set or reset the CCxNE Bit */
+ TIMx->CCER |= (u16)(TIM_CCxN << TIM_Channel);
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectOCxM
+* Description : Selects the TIM Ouput Compare Mode.
+* This function disables the selected channel before changing
+* the Ouput Compare Mode. User has to enable this channel using
+* TIM_CCxCmd and TIM_CCxNCmd functions.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_Channel: specifies the TIM Channel
+* This parmeter can be one of the following values:
+* - TIM_Channel_1: TIM Channel 1
+* - TIM_Channel_2: TIM Channel 2
+* - TIM_Channel_3: TIM Channel 3
+* - TIM_Channel_4: TIM Channel 4
+* - TIM_OCMode: specifies the TIM Output Compare Mode.
+* This paramter can be one of the following values:
+* - TIM_OCMode_Timing
+* - TIM_OCMode_Active
+* - TIM_OCMode_Toggle
+* - TIM_OCMode_PWM1
+* - TIM_OCMode_PWM2
+* - TIM_ForcedAction_Active
+* - TIM_ForcedAction_InActive
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectOCxM(TIM_TypeDef* TIMx, u16 TIM_Channel, u16 TIM_OCMode)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_CHANNEL(TIM_Channel));
+ assert_param(IS_TIM_OCM(TIM_OCMode));
+
+ /* Disable the Channel: Reset the CCxE Bit */
+ TIMx->CCER &= (u16)(~((u16)(CCER_CCE_Set << TIM_Channel)));
+
+ if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3))
+ {
+ /* Reset the OCxM bits in the CCMRx register */
+ *((vu32 *)((*(u32*)&TIMx) + CCMR_Offset + (TIM_Channel>>1))) &= CCMR_OC13M_Mask;
+
+ /* Configure the OCxM bits in the CCMRx register */
+ *((vu32 *)((*(u32*)&TIMx) + CCMR_Offset + (TIM_Channel>>1))) = TIM_OCMode;
+
+ }
+ else
+ {
+ /* Reset the OCxM bits in the CCMRx register */
+ *((vu32 *)((*(u32*)&TIMx) + CCMR_Offset + ((u16)(TIM_Channel - 4)>> 1))) &= CCMR_OC24M_Mask;
+
+ /* Configure the OCxM bits in the CCMRx register */
+ *((vu32 *)((*(u32*)&TIMx) + CCMR_Offset + ((u16)(TIM_Channel - 4)>> 1))) = (u16)(TIM_OCMode << 8);
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_UpdateDisableConfig
+* Description : Enables or Disables the TIMx Update event.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - NewState: new state of the TIMx UDIS bit
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Set the Update Disable Bit */
+ TIMx->CR1 |= CR1_UDIS_Set;
+ }
+ else
+ {
+ /* Reset the Update Disable Bit */
+ TIMx->CR1 &= CR1_UDIS_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_UpdateRequestConfig
+* Description : Configures the TIMx Update Request Interrupt source.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_UpdateSource: specifies the Update source.
+* This parameter can be one of the following values:
+* - TIM_UpdateSource_Regular
+* - TIM_UpdateSource_Global
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, u16 TIM_UpdateSource)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_UPDATE_SOURCE(TIM_UpdateSource));
+
+ if (TIM_UpdateSource != TIM_UpdateSource_Global)
+ {
+ /* Set the URS Bit */
+ TIMx->CR1 |= CR1_URS_Set;
+ }
+ else
+ {
+ /* Reset the URS Bit */
+ TIMx->CR1 &= CR1_URS_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectHallSensor
+* Description : Enables or disables the TIMx’s Hall sensor interface.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+* - NewState: new state of the TIMx Hall sensor interface.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Set the TI1S Bit */
+ TIMx->CR2 |= CR2_TI1S_Set;
+ }
+ else
+ {
+ /* Reset the TI1S Bit */
+ TIMx->CR2 &= CR2_TI1S_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectOnePulseMode
+* Description : Selects the TIMx’s One Pulse Mode.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_OPMode: specifies the OPM Mode to be used.
+* This parameter can be one of the following values:
+* - TIM_OPMode_Single
+* - TIM_OPMode_Repetitive
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, u16 TIM_OPMode)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_OPM_MODE(TIM_OPMode));
+
+ /* Reset the OPM Bit */
+ TIMx->CR1 &= CR1_OPM_Reset;
+
+ /* Configure the OPM Mode */
+ TIMx->CR1 |= TIM_OPMode;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectOutputTrigger
+* Description : Selects the TIMx Trigger Output Mode.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_TRGOSource: specifies the Trigger Output source.
+* This paramter can be as follow:
+* 1/ For TIM1 to TIM8:
+* - TIM_TRGOSource_Reset
+* - TIM_TRGOSource_Enable
+* - TIM_TRGOSource_Update
+* 2/ These parameters are available for all TIMx except
+* TIM6 and TIM7:
+* - TIM_TRGOSource_OC1
+* - TIM_TRGOSource_OC1Ref
+* - TIM_TRGOSource_OC2Ref
+* - TIM_TRGOSource_OC3Ref
+* - TIM_TRGOSource_OC4Ref
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, u16 TIM_TRGOSource)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_TRGO_SOURCE(TIM_TRGOSource));
+ assert_param(IS_TIM_PERIPH_TRGO(TIMx, TIM_TRGOSource));
+
+ /* Reset the MMS Bits */
+ TIMx->CR2 &= CR2_MMS_Mask;
+
+ /* Select the TRGO source */
+ TIMx->CR2 |= TIM_TRGOSource;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectSlaveMode
+* Description : Selects the TIMx Slave Mode.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_SlaveMode: specifies the Timer Slave Mode.
+* This paramter can be one of the following values:
+* - TIM_SlaveMode_Reset
+* - TIM_SlaveMode_Gated
+* - TIM_SlaveMode_Trigger
+* - TIM_SlaveMode_External1
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, u16 TIM_SlaveMode)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_SLAVE_MODE(TIM_SlaveMode));
+
+ /* Reset the SMS Bits */
+ TIMx->SMCR &= SMCR_SMS_Mask;
+
+ /* Select the Slave Mode */
+ TIMx->SMCR |= TIM_SlaveMode;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectMasterSlaveMode
+* Description : Sets or Resets the TIMx Master/Slave Mode.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_MasterSlaveMode: specifies the Timer Master Slave Mode.
+* This paramter can be one of the following values:
+* - TIM_MasterSlaveMode_Enable: synchronization between the
+* current timer and its slaves (through TRGO).
+* - TIM_MasterSlaveMode_Disable: No action
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, u16 TIM_MasterSlaveMode)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_MSM_STATE(TIM_MasterSlaveMode));
+
+ /* Reset the MSM Bit */
+ TIMx->SMCR &= SMCR_MSM_Reset;
+
+ /* Set or Reset the MSM Bit */
+ TIMx->SMCR |= TIM_MasterSlaveMode;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetCounter
+* Description : Sets the TIMx Counter Register value
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - Counter: specifies the Counter register new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetCounter(TIM_TypeDef* TIMx, u16 Counter)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+
+ /* Set the Counter Register value */
+ TIMx->CNT = Counter;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetAutoreload
+* Description : Sets the TIMx Autoreload Register value
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - Autoreload: specifies the Autoreload register new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetAutoreload(TIM_TypeDef* TIMx, u16 Autoreload)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+
+ /* Set the Autoreload Register value */
+ TIMx->ARR = Autoreload;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetCompare1
+* Description : Sets the TIMx Capture Compare1 Register value
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - Compare1: specifies the Capture Compare1 register new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetCompare1(TIM_TypeDef* TIMx, u16 Compare1)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Set the Capture Compare1 Register value */
+ TIMx->CCR1 = Compare1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetCompare2
+* Description : Sets the TIMx Capture Compare2 Register value
+* Input : TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - Compare2: specifies the Capture Compare2 register new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetCompare2(TIM_TypeDef* TIMx, u16 Compare2)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Set the Capture Compare2 Register value */
+ TIMx->CCR2 = Compare2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetCompare3
+* Description : Sets the TIMx Capture Compare3 Register value
+* Input : TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - Compare3: specifies the Capture Compare3 register new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetCompare3(TIM_TypeDef* TIMx, u16 Compare3)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Set the Capture Compare3 Register value */
+ TIMx->CCR3 = Compare3;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetCompare4
+* Description : Sets the TIMx Capture Compare4 Register value
+* Input : TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - Compare4: specifies the Capture Compare4 register new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetCompare4(TIM_TypeDef* TIMx, u16 Compare4)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Set the Capture Compare4 Register value */
+ TIMx->CCR4 = Compare4;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetIC1Prescaler
+* Description : Sets the TIMx Input Capture 1 prescaler.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPSC: specifies the Input Capture1 prescaler
+* new value.
+* This parameter can be one of the following values:
+* - TIM_ICPSC_DIV1: no prescaler
+* - TIM_ICPSC_DIV2: capture is done once every 2 events
+* - TIM_ICPSC_DIV4: capture is done once every 4 events
+* - TIM_ICPSC_DIV8: capture is done once every 8 events
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+
+ /* Reset the IC1PSC Bits */
+ TIMx->CCMR1 &= CCMR_IC13PSC_Mask;
+
+ /* Set the IC1PSC value */
+ TIMx->CCMR1 |= TIM_ICPSC;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetIC2Prescaler
+* Description : Sets the TIMx Input Capture 2 prescaler.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPSC: specifies the Input Capture2 prescaler
+* new value.
+* This parameter can be one of the following values:
+* - TIM_ICPSC_DIV1: no prescaler
+* - TIM_ICPSC_DIV2: capture is done once every 2 events
+* - TIM_ICPSC_DIV4: capture is done once every 4 events
+* - TIM_ICPSC_DIV8: capture is done once every 8 events
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+
+ /* Reset the IC2PSC Bits */
+ TIMx->CCMR1 &= CCMR_IC24PSC_Mask;
+
+ /* Set the IC2PSC value */
+ TIMx->CCMR1 |= (u16)(TIM_ICPSC << 8);
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetIC3Prescaler
+* Description : Sets the TIMx Input Capture 3 prescaler.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPSC: specifies the Input Capture3 prescaler
+* new value.
+* This parameter can be one of the following values:
+* - TIM_ICPSC_DIV1: no prescaler
+* - TIM_ICPSC_DIV2: capture is done once every 2 events
+* - TIM_ICPSC_DIV4: capture is done once every 4 events
+* - TIM_ICPSC_DIV8: capture is done once every 8 events
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+
+ /* Reset the IC3PSC Bits */
+ TIMx->CCMR2 &= CCMR_IC13PSC_Mask;
+
+ /* Set the IC3PSC value */
+ TIMx->CCMR2 |= TIM_ICPSC;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetIC4Prescaler
+* Description : Sets the TIMx Input Capture 4 prescaler.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPSC: specifies the Input Capture4 prescaler
+* new value.
+* This parameter can be one of the following values:
+* - TIM_ICPSC_DIV1: no prescaler
+* - TIM_ICPSC_DIV2: capture is done once every 2 events
+* - TIM_ICPSC_DIV4: capture is done once every 4 events
+* - TIM_ICPSC_DIV8: capture is done once every 8 events
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+
+ /* Reset the IC4PSC Bits */
+ TIMx->CCMR2 &= CCMR_IC24PSC_Mask;
+
+ /* Set the IC4PSC value */
+ TIMx->CCMR2 |= (u16)(TIM_ICPSC << 8);
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetClockDivision
+* Description : Sets the TIMx Clock Division value.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_CKD: specifies the clock division value.
+* This parameter can be one of the following value:
+* - TIM_CKD_DIV1: TDTS = Tck_tim
+* - TIM_CKD_DIV2: TDTS = 2*Tck_tim
+* - TIM_CKD_DIV4: TDTS = 4*Tck_tim
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetClockDivision(TIM_TypeDef* TIMx, u16 TIM_CKD)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_CKD_DIV(TIM_CKD));
+
+ /* Reset the CKD Bits */
+ TIMx->CR1 &= CR1_CKD_Mask;
+
+ /* Set the CKD value */
+ TIMx->CR1 |= TIM_CKD;
+}
+/*******************************************************************************
+* Function Name : TIM_GetCapture1
+* Description : Gets the TIMx Input Capture 1 value.
+* Input : TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* Output : None
+* Return : Capture Compare 1 Register value.
+*******************************************************************************/
+u16 TIM_GetCapture1(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Get the Capture 1 Register value */
+ return TIMx->CCR1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_GetCapture2
+* Description : Gets the TIMx Input Capture 2 value.
+* Input : TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* Output : None
+* Return : Capture Compare 2 Register value.
+*******************************************************************************/
+u16 TIM_GetCapture2(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Get the Capture 2 Register value */
+ return TIMx->CCR2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_GetCapture3
+* Description : Gets the TIMx Input Capture 3 value.
+* Input : TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* Output : None
+* Return : Capture Compare 3 Register value.
+*******************************************************************************/
+u16 TIM_GetCapture3(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Get the Capture 3 Register value */
+ return TIMx->CCR3;
+}
+
+/*******************************************************************************
+* Function Name : TIM_GetCapture4
+* Description : Gets the TIMx Input Capture 4 value.
+* Input : TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* Output : None
+* Return : Capture Compare 4 Register value.
+*******************************************************************************/
+u16 TIM_GetCapture4(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Get the Capture 4 Register value */
+ return TIMx->CCR4;
+}
+
+/*******************************************************************************
+* Function Name : TIM_GetCounter
+* Description : Gets the TIMx Counter value.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* Output : None
+* Return : Counter Register value.
+*******************************************************************************/
+u16 TIM_GetCounter(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+
+ /* Get the Counter Register value */
+ return TIMx->CNT;
+}
+
+/*******************************************************************************
+* Function Name : TIM_GetPrescaler
+* Description : Gets the TIMx Prescaler value.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* Output : None
+* Return : Prescaler Register value.
+*******************************************************************************/
+u16 TIM_GetPrescaler(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+
+ /* Get the Prescaler Register value */
+ return TIMx->PSC;
+}
+
+/*******************************************************************************
+* Function Name : TIM_GetFlagStatus
+* Description : Checks whether the specified TIM flag is set or not.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - TIM_FLAG_Update: TIM update Flag
+* - TIM_FLAG_CC1: TIM Capture Compare 1 Flag
+* - TIM_FLAG_CC2: TIM Capture Compare 2 Flag
+* - TIM_FLAG_CC3: TIM Capture Compare 3 Flag
+* - TIM_FLAG_CC4: TIM Capture Compare 4 Flag
+* - TIM_FLAG_COM: TIM Commutation Flag
+* - TIM_FLAG_Trigger: TIM Trigger Flag
+* - TIM_FLAG_Break: TIM Break Flag
+* - TIM_FLAG_CC1OF: TIM Capture Compare 1 overcapture Flag
+* - TIM_FLAG_CC2OF: TIM Capture Compare 2 overcapture Flag
+* - TIM_FLAG_CC3OF: TIM Capture Compare 3 overcapture Flag
+* - TIM_FLAG_CC4OF: TIM Capture Compare 4 overcapture Flag
+* Output : None
+* Return : The new state of TIM_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, u16 TIM_FLAG)
+{
+ ITStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_GET_FLAG(TIM_FLAG));
+ assert_param(IS_TIM_PERIPH_FLAG(TIMx, TIM_FLAG));
+
+ if ((TIMx->SR & TIM_FLAG) != (u16)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ClearFlag
+* Description : Clears the TIMx's pending flags.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_FLAG: specifies the flag bit to clear.
+* This parameter can be any combination of the following values:
+* - TIM_FLAG_Update: TIM update Flag
+* - TIM_FLAG_CC1: TIM Capture Compare 1 Flag
+* - TIM_FLAG_CC2: TIM Capture Compare 2 Flag
+* - TIM_FLAG_CC3: TIM Capture Compare 3 Flag
+* - TIM_FLAG_CC4: TIM Capture Compare 4 Flag
+* - TIM_FLAG_COM: TIM Commutation Flag
+* - TIM_FLAG_Trigger: TIM Trigger Flag
+* - TIM_FLAG_Break: TIM Break Flag
+* - TIM_FLAG_CC1OF: TIM Capture Compare 1 overcapture Flag
+* - TIM_FLAG_CC2OF: TIM Capture Compare 2 overcapture Flag
+* - TIM_FLAG_CC3OF: TIM Capture Compare 3 overcapture Flag
+* - TIM_FLAG_CC4OF: TIM Capture Compare 4 overcapture Flag
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ClearFlag(TIM_TypeDef* TIMx, u16 TIM_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_CLEAR_FLAG(TIMx, TIM_FLAG));
+ assert_param(IS_TIM_PERIPH_FLAG(TIMx, TIM_FLAG));
+
+ /* Clear the flags */
+ TIMx->SR = (u16)~TIM_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : TIM_GetITStatus
+* Description : Checks whether the TIM interrupt has occurred or not.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_IT: specifies the TIM interrupt source to check.
+* This parameter can be one of the following values:
+* - TIM_IT_Update: TIM update Interrupt source
+* - TIM_IT_CC1: TIM Capture Compare 1 Interrupt source
+* - TIM_IT_CC2: TIM Capture Compare 2 Interrupt source
+* - TIM_IT_CC3: TIM Capture Compare 3 Interrupt source
+* - TIM_IT_CC4: TIM Capture Compare 4 Interrupt source
+* - TIM_IT_COM: TIM Commutation Interrupt
+* source
+* - TIM_IT_Trigger: TIM Trigger Interrupt source
+* - TIM_IT_Break: TIM Break Interrupt source
+* Output : None
+* Return : The new state of the TIM_IT(SET or RESET).
+*******************************************************************************/
+ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, u16 TIM_IT)
+{
+ ITStatus bitstatus = RESET;
+ u16 itstatus = 0x0, itenable = 0x0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_GET_IT(TIM_IT));
+ assert_param(IS_TIM_PERIPH_IT(TIMx, TIM_IT));
+
+ itstatus = TIMx->SR & TIM_IT;
+
+ itenable = TIMx->DIER & TIM_IT;
+
+ if ((itstatus != (u16)RESET) && (itenable != (u16)RESET))
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ClearITPendingBit
+* Description : Clears the TIMx's interrupt pending bits.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_IT: specifies the pending bit to clear.
+* This parameter can be any combination of the following values:
+* - TIM_IT_Update: TIM1 update Interrupt source
+* - TIM_IT_CC1: TIM Capture Compare 1 Interrupt source
+* - TIM_IT_CC2: TIM Capture Compare 2 Interrupt source
+* - TIM_IT_CC3: TIM Capture Compare 3 Interrupt source
+* - TIM_IT_CC4: TIM Capture Compare 4 Interrupt source
+* - TIM_IT_COM: TIM Commutation Interrupt
+* source
+* - TIM_IT_Trigger: TIM Trigger Interrupt source
+* - TIM_IT_Break: TIM Break Interrupt source
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, u16 TIM_IT)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_PERIPH_IT(TIMx, TIM_IT));
+
+ /* Clear the IT pending Bit */
+ TIMx->SR = (u16)~TIM_IT;
+}
+
+/*******************************************************************************
+* Function Name : TI1_Config
+* Description : Configure the TI1 as Input.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPolarity : The Input Polarity.
+* This parameter can be one of the following values:
+* - TIM_ICPolarity_Rising
+* - TIM_ICPolarity_Falling
+* - TIM_ICSelection: specifies the input to be used.
+* This parameter can be one of the following values:
+* - TIM_ICSelection_DirectTI: TIM Input 1 is selected to
+* be connected to IC1.
+* - TIM_ICSelection_IndirectTI: TIM Input 1 is selected to
+* be connected to IC2.
+* - TIM_ICSelection_TRC: TIM Input 1 is selected to be
+* connected to TRC.
+* - TIM_ICFilter: Specifies the Input Capture Filter.
+* This parameter must be a value between 0x00 and 0x0F.
+* Output : None
+* Return : None
+*******************************************************************************/
+static void TI1_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter)
+{
+ u16 tmpccmr1 = 0, tmpccer = 0;
+
+ /* Disable the Channel 1: Reset the CC1E Bit */
+ TIMx->CCER &= CCER_CC1E_Reset;
+
+ tmpccmr1 = TIMx->CCMR1;
+ tmpccer = TIMx->CCER;
+
+ /* Select the Input and set the filter */
+ tmpccmr1 &= CCMR_CC13S_Mask & CCMR_IC13F_Mask;
+ tmpccmr1 |= TIM_ICSelection | (u16)(TIM_ICFilter << 4);
+
+ /* Select the Polarity and set the CC1E Bit */
+ tmpccer &= CCER_CC1P_Reset;
+ tmpccer |= TIM_ICPolarity | CCER_CC1E_Set;
+
+ /* Write to TIMx CCMR1 and CCER registers */
+ TIMx->CCMR1 = tmpccmr1;
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TI2_Config
+* Description : Configure the TI2 as Input.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPolarity : The Input Polarity.
+* This parameter can be one of the following values:
+* - TIM_ICPolarity_Rising
+* - TIM_ICPolarity_Falling
+* - TIM_ICSelection: specifies the input to be used.
+* This parameter can be one of the following values:
+* - TIM_ICSelection_DirectTI: TIM Input 2 is selected to
+* be connected to IC2.
+* - TIM_ICSelection_IndirectTI: TIM Input 2 is selected to
+* be connected to IC1.
+* - TIM_ICSelection_TRC: TIM Input 2 is selected to be
+* connected to TRC.
+* - TIM_ICFilter: Specifies the Input Capture Filter.
+* This parameter must be a value between 0x00 and 0x0F.
+* Output : None
+* Return : None
+*******************************************************************************/
+static void TI2_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter)
+{
+ u16 tmpccmr1 = 0, tmpccer = 0, tmp = 0;
+
+ /* Disable the Channel 2: Reset the CC2E Bit */
+ TIMx->CCER &= CCER_CC2E_Reset;
+
+ tmpccmr1 = TIMx->CCMR1;
+ tmpccer = TIMx->CCER;
+ tmp = (u16)(TIM_ICPolarity << 4);
+
+ /* Select the Input and set the filter */
+ tmpccmr1 &= CCMR_CC24S_Mask & CCMR_IC24F_Mask;
+ tmpccmr1 |= (u16)(TIM_ICFilter << 12);
+ tmpccmr1 |= (u16)(TIM_ICSelection << 8);
+
+ /* Select the Polarity and set the CC2E Bit */
+ tmpccer &= CCER_CC2P_Reset;
+ tmpccer |= tmp | CCER_CC2E_Set;
+
+ /* Write to TIMx CCMR1 and CCER registers */
+ TIMx->CCMR1 = tmpccmr1 ;
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TI3_Config
+* Description : Configure the TI3 as Input.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPolarity : The Input Polarity.
+* This parameter can be one of the following values:
+* - TIM_ICPolarity_Rising
+* - TIM_ICPolarity_Falling
+* - TIM_ICSelection: specifies the input to be used.
+* This parameter can be one of the following values:
+* - TIM_ICSelection_DirectTI: TIM Input 3 is selected to
+* be connected to IC3.
+* - TIM_ICSelection_IndirectTI: TIM Input 3 is selected to
+* be connected to IC4.
+* - TIM_ICSelection_TRC: TIM Input 3 is selected to be
+* connected to TRC.
+* - TIM_ICFilter: Specifies the Input Capture Filter.
+* This parameter must be a value between 0x00 and 0x0F.
+* Output : None
+* Return : None
+*******************************************************************************/
+static void TI3_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter)
+{
+ u16 tmpccmr2 = 0, tmpccer = 0, tmp = 0;
+
+ /* Disable the Channel 3: Reset the CC3E Bit */
+ TIMx->CCER &= CCER_CC3E_Reset;
+
+ tmpccmr2 = TIMx->CCMR2;
+ tmpccer = TIMx->CCER;
+ tmp = (u16)(TIM_ICPolarity << 8);
+
+ /* Select the Input and set the filter */
+ tmpccmr2 &= CCMR_CC13S_Mask & CCMR_IC13F_Mask;
+ tmpccmr2 |= TIM_ICSelection | (u16)(TIM_ICFilter << 4);
+
+ /* Select the Polarity and set the CC3E Bit */
+ tmpccer &= CCER_CC3P_Reset;
+ tmpccer |= tmp | CCER_CC3E_Set;
+
+ /* Write to TIMx CCMR2 and CCER registers */
+ TIMx->CCMR2 = tmpccmr2;
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TI4_Config
+* Description : Configure the TI1 as Input.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPolarity : The Input Polarity.
+* This parameter can be one of the following values:
+* - TIM_ICPolarity_Rising
+* - TIM_ICPolarity_Falling
+* - TIM_ICSelection: specifies the input to be used.
+* This parameter can be one of the following values:
+* - TIM_ICSelection_DirectTI: TIM Input 4 is selected to
+* be connected to IC4.
+* - TIM_ICSelection_IndirectTI: TIM Input 4 is selected to
+* be connected to IC3.
+* - TIM_ICSelection_TRC: TIM Input 4 is selected to be
+* connected to TRC.
+* - TIM_ICFilter: Specifies the Input Capture Filter.
+* This parameter must be a value between 0x00 and 0x0F.
+* Output : None
+* Return : None
+*******************************************************************************/
+static void TI4_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter)
+{
+ u16 tmpccmr2 = 0, tmpccer = 0, tmp = 0;
+
+ /* Disable the Channel 4: Reset the CC4E Bit */
+ TIMx->CCER &= CCER_CC4E_Reset;
+
+ tmpccmr2 = TIMx->CCMR2;
+ tmpccer = TIMx->CCER;
+ tmp = (u16)(TIM_ICPolarity << 12);
+
+ /* Select the Input and set the filter */
+ tmpccmr2 &= CCMR_CC24S_Mask & CCMR_IC24F_Mask;
+ tmpccmr2 |= (u16)(TIM_ICSelection << 8) | (u16)(TIM_ICFilter << 12);
+
+ /* Select the Polarity and set the CC4E Bit */
+ tmpccer &= CCER_CC4P_Reset;
+ tmpccer |= tmp | CCER_CC4E_Set;
+
+ /* Write to TIMx CCMR2 and CCER registers */
+ TIMx->CCMR2 = tmpccmr2;
+ TIMx->CCER = tmpccer ;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_usart.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_usart.c new file mode 100755 index 0000000..261462b --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_usart.c @@ -0,0 +1,989 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_usart.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the USART firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_usart.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* USART UE Mask */
+#define CR1_UE_Set ((u16)0x2000) /* USART Enable Mask */
+#define CR1_UE_Reset ((u16)0xDFFF) /* USART Disable Mask */
+
+/* USART WakeUp Method */
+#define CR1_WAKE_Mask ((u16)0xF7FF) /* USART WakeUp Method Mask */
+
+/* USART RWU Mask */
+#define CR1_RWU_Set ((u16)0x0002) /* USART mute mode Enable Mask */
+#define CR1_RWU_Reset ((u16)0xFFFD) /* USART mute mode Enable Mask */
+
+#define CR1_SBK_Set ((u16)0x0001) /* USART Break Character send Mask */
+
+#define CR1_CLEAR_Mask ((u16)0xE9F3) /* USART CR1 Mask */
+
+#define CR2_Address_Mask ((u16)0xFFF0) /* USART address Mask */
+
+/* USART LIN Mask */
+#define CR2_LINEN_Set ((u16)0x4000) /* USART LIN Enable Mask */
+#define CR2_LINEN_Reset ((u16)0xBFFF) /* USART LIN Disable Mask */
+
+/* USART LIN Break detection */
+#define CR2_LBDL_Mask ((u16)0xFFDF) /* USART LIN Break detection Mask */
+
+#define CR2_STOP_CLEAR_Mask ((u16)0xCFFF) /* USART CR2 STOP Bits Mask */
+#define CR2_CLOCK_CLEAR_Mask ((u16)0xF0FF) /* USART CR2 Clock Mask */
+
+/* USART SC Mask */
+#define CR3_SCEN_Set ((u16)0x0020) /* USART SC Enable Mask */
+#define CR3_SCEN_Reset ((u16)0xFFDF) /* USART SC Disable Mask */
+
+/* USART SC NACK Mask */
+#define CR3_NACK_Set ((u16)0x0010) /* USART SC NACK Enable Mask */
+#define CR3_NACK_Reset ((u16)0xFFEF) /* USART SC NACK Disable Mask */
+
+/* USART Half-Duplex Mask */
+#define CR3_HDSEL_Set ((u16)0x0008) /* USART Half-Duplex Enable Mask */
+#define CR3_HDSEL_Reset ((u16)0xFFF7) /* USART Half-Duplex Disable Mask */
+
+/* USART IrDA Mask */
+#define CR3_IRLP_Mask ((u16)0xFFFB) /* USART IrDA LowPower mode Mask */
+
+#define CR3_CLEAR_Mask ((u16)0xFCFF) /* USART CR3 Mask */
+
+/* USART IrDA Mask */
+#define CR3_IREN_Set ((u16)0x0002) /* USART IrDA Enable Mask */
+#define CR3_IREN_Reset ((u16)0xFFFD) /* USART IrDA Disable Mask */
+
+#define GTPR_LSB_Mask ((u16)0x00FF) /* Guard Time Register LSB Mask */
+#define GTPR_MSB_Mask ((u16)0xFF00) /* Guard Time Register MSB Mask */
+
+#define IT_Mask ((u16)0x001F) /* USART Interrupt Mask */
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : USART_DeInit
+* Description : Deinitializes the USARTx peripheral registers to their
+* default reset values.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_DeInit(USART_TypeDef* USARTx)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+
+ switch (*(u32*)&USARTx)
+ {
+ case USART1_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, DISABLE);
+ break;
+
+ case USART2_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, DISABLE);
+ break;
+
+ case USART3_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, DISABLE);
+ break;
+
+ case UART4_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, DISABLE);
+ break;
+
+ case UART5_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, DISABLE);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_Init
+* Description : Initializes the USARTx peripheral according to the specified
+* parameters in the USART_InitStruct .
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_InitStruct: pointer to a USART_InitTypeDef structure
+* that contains the configuration information for the
+* specified USART peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct)
+{
+ u32 tmpreg = 0x00, apbclock = 0x00;
+ u32 integerdivider = 0x00;
+ u32 fractionaldivider = 0x00;
+ u32 usartxbase = 0;
+ RCC_ClocksTypeDef RCC_ClocksStatus;
+
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_BAUDRATE(USART_InitStruct->USART_BaudRate));
+ assert_param(IS_USART_WORD_LENGTH(USART_InitStruct->USART_WordLength));
+ assert_param(IS_USART_STOPBITS(USART_InitStruct->USART_StopBits));
+ assert_param(IS_USART_PARITY(USART_InitStruct->USART_Parity));
+ assert_param(IS_USART_MODE(USART_InitStruct->USART_Mode));
+ assert_param(IS_USART_HARDWARE_FLOW_CONTROL(USART_InitStruct->USART_HardwareFlowControl));
+ /* The hardware flow control is available only for USART1, USART2 and USART3 */
+ assert_param(IS_USART_PERIPH_HFC(USARTx, USART_InitStruct->USART_HardwareFlowControl));
+
+ usartxbase = (*(u32*)&USARTx);
+
+/*---------------------------- USART CR2 Configuration -----------------------*/
+ tmpreg = USARTx->CR2;
+ /* Clear STOP[13:12] bits */
+ tmpreg &= CR2_STOP_CLEAR_Mask;
+
+ /* Configure the USART Stop Bits, Clock, CPOL, CPHA and LastBit ------------*/
+ /* Set STOP[13:12] bits according to USART_StopBits value */
+ tmpreg |= (u32)USART_InitStruct->USART_StopBits;
+
+ /* Write to USART CR2 */
+ USARTx->CR2 = (u16)tmpreg;
+
+/*---------------------------- USART CR1 Configuration -----------------------*/
+ tmpreg = USARTx->CR1;
+ /* Clear M, PCE, PS, TE and RE bits */
+ tmpreg &= CR1_CLEAR_Mask;
+
+ /* Configure the USART Word Length, Parity and mode ----------------------- */
+ /* Set the M bits according to USART_WordLength value */
+ /* Set PCE and PS bits according to USART_Parity value */
+ /* Set TE and RE bits according to USART_Mode value */
+ tmpreg |= (u32)USART_InitStruct->USART_WordLength | USART_InitStruct->USART_Parity |
+ USART_InitStruct->USART_Mode;
+
+ /* Write to USART CR1 */
+ USARTx->CR1 = (u16)tmpreg;
+
+/*---------------------------- USART CR3 Configuration -----------------------*/
+ tmpreg = USARTx->CR3;
+ /* Clear CTSE and RTSE bits */
+ tmpreg &= CR3_CLEAR_Mask;
+
+ /* Configure the USART HFC -------------------------------------------------*/
+ /* Set CTSE and RTSE bits according to USART_HardwareFlowControl value */
+ tmpreg |= USART_InitStruct->USART_HardwareFlowControl;
+
+ /* Write to USART CR3 */
+ USARTx->CR3 = (u16)tmpreg;
+
+/*---------------------------- USART BRR Configuration -----------------------*/
+ /* Configure the USART Baud Rate -------------------------------------------*/
+ RCC_GetClocksFreq(&RCC_ClocksStatus);
+ if (usartxbase == USART1_BASE)
+ {
+ apbclock = RCC_ClocksStatus.PCLK2_Frequency;
+ }
+ else
+ {
+ apbclock = RCC_ClocksStatus.PCLK1_Frequency;
+ }
+
+ /* Determine the integer part */
+ integerdivider = ((0x19 * apbclock) / (0x04 * (USART_InitStruct->USART_BaudRate)));
+ tmpreg = (integerdivider / 0x64) << 0x04;
+
+ /* Determine the fractional part */
+ fractionaldivider = integerdivider - (0x64 * (tmpreg >> 0x04));
+ tmpreg |= ((((fractionaldivider * 0x10) + 0x32) / 0x64)) & ((u8)0x0F);
+
+ /* Write to USART BRR */
+ USARTx->BRR = (u16)tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : USART_StructInit
+* Description : Fills each USART_InitStruct member with its default value.
+* Input : - USART_InitStruct: pointer to a USART_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_StructInit(USART_InitTypeDef* USART_InitStruct)
+{
+ /* USART_InitStruct members default value */
+ USART_InitStruct->USART_BaudRate = 9600;
+ USART_InitStruct->USART_WordLength = USART_WordLength_8b;
+ USART_InitStruct->USART_StopBits = USART_StopBits_1;
+ USART_InitStruct->USART_Parity = USART_Parity_No ;
+ USART_InitStruct->USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+ USART_InitStruct->USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+}
+
+/*******************************************************************************
+* Function Name : USART_ClockInit
+* Description : Initializes the USARTx peripheral Clock according to the
+* specified parameters in the USART_ClockInitStruct .
+* Input : - USARTx: where x can be 1, 2, 3 to select the USART peripheral.
+* Note: The Smart Card mode is not available for UART4 and UART5.
+* - USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef
+* structure that contains the configuration information for
+* the specified USART peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct)
+{
+ u32 tmpreg = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_USART_123_PERIPH(USARTx));
+ assert_param(IS_USART_CLOCK(USART_ClockInitStruct->USART_Clock));
+ assert_param(IS_USART_CPOL(USART_ClockInitStruct->USART_CPOL));
+ assert_param(IS_USART_CPHA(USART_ClockInitStruct->USART_CPHA));
+ assert_param(IS_USART_LASTBIT(USART_ClockInitStruct->USART_LastBit));
+
+/*---------------------------- USART CR2 Configuration -----------------------*/
+ tmpreg = USARTx->CR2;
+ /* Clear CLKEN, CPOL, CPHA and LBCL bits */
+ tmpreg &= CR2_CLOCK_CLEAR_Mask;
+
+ /* Configure the USART Clock, CPOL, CPHA and LastBit ------------*/
+ /* Set CLKEN bit according to USART_Clock value */
+ /* Set CPOL bit according to USART_CPOL value */
+ /* Set CPHA bit according to USART_CPHA value */
+ /* Set LBCL bit according to USART_LastBit value */
+ tmpreg |= (u32)USART_ClockInitStruct->USART_Clock | USART_ClockInitStruct->USART_CPOL |
+ USART_ClockInitStruct->USART_CPHA | USART_ClockInitStruct->USART_LastBit;
+
+ /* Write to USART CR2 */
+ USARTx->CR2 = (u16)tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : USART_ClockStructInit
+* Description : Fills each USART_ClockInitStruct member with its default value.
+* Input : - USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct)
+{
+ /* USART_ClockInitStruct members default value */
+ USART_ClockInitStruct->USART_Clock = USART_Clock_Disable;
+ USART_ClockInitStruct->USART_CPOL = USART_CPOL_Low;
+ USART_ClockInitStruct->USART_CPHA = USART_CPHA_1Edge;
+ USART_ClockInitStruct->USART_LastBit = USART_LastBit_Disable;
+}
+
+/*******************************************************************************
+* Function Name : USART_Cmd
+* Description : Enables or disables the specified USART peripheral.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* : - NewState: new state of the USARTx peripheral.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected USART by setting the UE bit in the CR1 register */
+ USARTx->CR1 |= CR1_UE_Set;
+ }
+ else
+ {
+ /* Disable the selected USART by clearing the UE bit in the CR1 register */
+ USARTx->CR1 &= CR1_UE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_ITConfig
+* Description : Enables or disables the specified USART interrupts.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_IT: specifies the USART interrupt sources to be
+* enabled or disabled.
+* This parameter can be one of the following values:
+* - USART_IT_CTS: CTS change interrupt (not available for
+* UART4 and UART5)
+* - USART_IT_LBD: LIN Break detection interrupt
+* - USART_IT_TXE: Tansmit Data Register empty interrupt
+* - USART_IT_TC: Transmission complete interrupt
+* - USART_IT_RXNE: Receive Data register not empty
+* interrupt
+* - USART_IT_IDLE: Idle line detection interrupt
+* - USART_IT_PE: Parity Error interrupt
+* - USART_IT_ERR: Error interrupt(Frame error, noise
+* error, overrun error)
+* - NewState: new state of the specified USARTx interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_ITConfig(USART_TypeDef* USARTx, u16 USART_IT, FunctionalState NewState)
+{
+ u32 usartreg = 0x00, itpos = 0x00, itmask = 0x00;
+ u32 usartxbase = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_CONFIG_IT(USART_IT));
+ assert_param(IS_USART_PERIPH_IT(USARTx, USART_IT)); /* The CTS interrupt is not available for UART4 and UART5 */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ usartxbase = (*(u32*)&(USARTx));
+
+ /* Get the USART register index */
+ usartreg = (((u8)USART_IT) >> 0x05);
+
+ /* Get the interrupt position */
+ itpos = USART_IT & IT_Mask;
+
+ itmask = (((u32)0x01) << itpos);
+
+ if (usartreg == 0x01) /* The IT is in CR1 register */
+ {
+ usartxbase += 0x0C;
+ }
+ else if (usartreg == 0x02) /* The IT is in CR2 register */
+ {
+ usartxbase += 0x10;
+ }
+ else /* The IT is in CR3 register */
+ {
+ usartxbase += 0x14;
+ }
+ if (NewState != DISABLE)
+ {
+ *(vu32*)usartxbase |= itmask;
+ }
+ else
+ {
+ *(vu32*)usartxbase &= ~itmask;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_DMACmd
+* Description : Enables or disables the USART’s DMA interface.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3 or UART4.
+* Note: The DMA mode is not available for UART5.
+* - USART_DMAReq: specifies the DMA request.
+* This parameter can be any combination of the following values:
+* - USART_DMAReq_Tx: USART DMA transmit request
+* - USART_DMAReq_Rx: USART DMA receive request
+* - NewState: new state of the DMA Request sources.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_DMACmd(USART_TypeDef* USARTx, u16 USART_DMAReq, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_1234_PERIPH(USARTx));
+ assert_param(IS_USART_DMAREQ(USART_DMAReq));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the DMA transfer for selected requests by setting the DMAT and/or
+ DMAR bits in the USART CR3 register */
+ USARTx->CR3 |= USART_DMAReq;
+ }
+ else
+ {
+ /* Disable the DMA transfer for selected requests by clearing the DMAT and/or
+ DMAR bits in the USART CR3 register */
+ USARTx->CR3 &= (u16)~USART_DMAReq;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_SetAddress
+* Description : Sets the address of the USART node.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_Address: Indicates the address of the USART node.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_SetAddress(USART_TypeDef* USARTx, u8 USART_Address)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_ADDRESS(USART_Address));
+
+ /* Clear the USART address */
+ USARTx->CR2 &= CR2_Address_Mask;
+ /* Set the USART address node */
+ USARTx->CR2 |= USART_Address;
+}
+
+/*******************************************************************************
+* Function Name : USART_WakeUpConfig
+* Description : Selects the USART WakeUp method.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_WakeUp: specifies the USART wakeup method.
+* This parameter can be one of the following values:
+* - USART_WakeUp_IdleLine: WakeUp by an idle line detection
+* - USART_WakeUp_AddressMark: WakeUp by an address mark
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_WakeUpConfig(USART_TypeDef* USARTx, u16 USART_WakeUp)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_WAKEUP(USART_WakeUp));
+
+ USARTx->CR1 &= CR1_WAKE_Mask;
+ USARTx->CR1 |= USART_WakeUp;
+}
+
+/*******************************************************************************
+* Function Name : USART_ReceiverWakeUpCmd
+* Description : Determines if the USART is in mute mode or not.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - NewState: new state of the USART mute mode.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the USART mute mode by setting the RWU bit in the CR1 register */
+ USARTx->CR1 |= CR1_RWU_Set;
+ }
+ else
+ {
+ /* Disable the USART mute mode by clearing the RWU bit in the CR1 register */
+ USARTx->CR1 &= CR1_RWU_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_LINBreakDetectLengthConfig
+* Description : Sets the USART LIN Break detection length.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_LINBreakDetectLength: specifies the LIN break
+* detection length.
+* This parameter can be one of the following values:
+* - USART_LINBreakDetectLength_10b: 10-bit break detection
+* - USART_LINBreakDetectLength_11b: 11-bit break detection
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, u16 USART_LINBreakDetectLength)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_LIN_BREAK_DETECT_LENGTH(USART_LINBreakDetectLength));
+
+ USARTx->CR2 &= CR2_LBDL_Mask;
+ USARTx->CR2 |= USART_LINBreakDetectLength;
+}
+
+/*******************************************************************************
+* Function Name : USART_LINCmd
+* Description : Enables or disables the USART’s LIN mode.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - NewState: new state of the USART LIN mode.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the LIN mode by setting the LINEN bit in the CR2 register */
+ USARTx->CR2 |= CR2_LINEN_Set;
+ }
+ else
+ {
+ /* Disable the LIN mode by clearing the LINEN bit in the CR2 register */
+ USARTx->CR2 &= CR2_LINEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_SendData
+* Description : Transmits single data through the USARTx peripheral.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - Data: the data to transmit.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_SendData(USART_TypeDef* USARTx, u16 Data)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_DATA(Data));
+
+ /* Transmit Data */
+ USARTx->DR = (Data & (u16)0x01FF);
+}
+
+/*******************************************************************************
+* Function Name : USART_ReceiveData
+* Description : Returns the most recent received data by the USARTx peripheral.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* Output : None
+* Return : The received data.
+*******************************************************************************/
+u16 USART_ReceiveData(USART_TypeDef* USARTx)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+
+ /* Receive Data */
+ return (u16)(USARTx->DR & (u16)0x01FF);
+}
+
+/*******************************************************************************
+* Function Name : USART_SendBreak
+* Description : Transmits break characters.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_SendBreak(USART_TypeDef* USARTx)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+
+ /* Send break characters */
+ USARTx->CR1 |= CR1_SBK_Set;
+}
+
+/*******************************************************************************
+* Function Name : USART_SetGuardTime
+* Description : Sets the specified USART guard time.
+* Input : - USARTx: where x can be 1, 2 or 3 to select the USART
+* peripheral.
+* Note: The guard time bits are not available for UART4 and UART5.
+* - USART_GuardTime: specifies the guard time.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_SetGuardTime(USART_TypeDef* USARTx, u8 USART_GuardTime)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_123_PERIPH(USARTx));
+
+ /* Clear the USART Guard time */
+ USARTx->GTPR &= GTPR_LSB_Mask;
+ /* Set the USART guard time */
+ USARTx->GTPR |= (u16)((u16)USART_GuardTime << 0x08);
+}
+
+/*******************************************************************************
+* Function Name : USART_SetPrescaler
+* Description : Sets the system clock prescaler.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* Note: The function is used for IrDA mode with UART4 and UART5.
+* - USART_Prescaler: specifies the prescaler clock.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_SetPrescaler(USART_TypeDef* USARTx, u8 USART_Prescaler)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+
+ /* Clear the USART prescaler */
+ USARTx->GTPR &= GTPR_MSB_Mask;
+ /* Set the USART prescaler */
+ USARTx->GTPR |= USART_Prescaler;
+}
+
+/*******************************************************************************
+* Function Name : USART_SmartCardCmd
+* Description : Enables or disables the USART’s Smart Card mode.
+* Input : - USARTx: where x can be 1, 2 or 3 to select the USART
+* peripheral.
+* Note: The Smart Card mode is not available for UART4 and UART5.
+* - NewState: new state of the Smart Card mode.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_123_PERIPH(USARTx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the SC mode by setting the SCEN bit in the CR3 register */
+ USARTx->CR3 |= CR3_SCEN_Set;
+ }
+ else
+ {
+ /* Disable the SC mode by clearing the SCEN bit in the CR3 register */
+ USARTx->CR3 &= CR3_SCEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_SmartCardNACKCmd
+* Description : Enables or disables NACK transmission.
+* Input : - USARTx: where x can be 1, 2 or 3 to select the USART
+* peripheral.
+* Note: The Smart Card mode is not available for UART4 and UART5.
+* - NewState: new state of the NACK transmission.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_123_PERIPH(USARTx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the NACK transmission by setting the NACK bit in the CR3 register */
+ USARTx->CR3 |= CR3_NACK_Set;
+ }
+ else
+ {
+ /* Disable the NACK transmission by clearing the NACK bit in the CR3 register */
+ USARTx->CR3 &= CR3_NACK_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_HalfDuplexCmd
+* Description : Enables or disables the USART’s Half Duplex communication.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - NewState: new state of the USART Communication.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */
+ USARTx->CR3 |= CR3_HDSEL_Set;
+ }
+ else
+ {
+ /* Disable the Half-Duplex mode by clearing the HDSEL bit in the CR3 register */
+ USARTx->CR3 &= CR3_HDSEL_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_IrDAConfig
+* Description : Configures the USART’s IrDA interface.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_IrDAMode: specifies the IrDA mode.
+* This parameter can be one of the following values:
+* - USART_IrDAMode_LowPower
+* - USART_IrDAMode_Normal
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_IrDAConfig(USART_TypeDef* USARTx, u16 USART_IrDAMode)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_IRDA_MODE(USART_IrDAMode));
+
+ USARTx->CR3 &= CR3_IRLP_Mask;
+ USARTx->CR3 |= USART_IrDAMode;
+}
+
+/*******************************************************************************
+* Function Name : USART_IrDACmd
+* Description : Enables or disables the USART’s IrDA interface.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - NewState: new state of the IrDA mode.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the IrDA mode by setting the IREN bit in the CR3 register */
+ USARTx->CR3 |= CR3_IREN_Set;
+ }
+ else
+ {
+ /* Disable the IrDA mode by clearing the IREN bit in the CR3 register */
+ USARTx->CR3 &= CR3_IREN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_GetFlagStatus
+* Description : Checks whether the specified USART flag is set or not.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - USART_FLAG_CTS: CTS Change flag (not available for
+* UART4 and UART5)
+* - USART_FLAG_LBD: LIN Break detection flag
+* - USART_FLAG_TXE: Transmit data register empty flag
+* - USART_FLAG_TC: Transmission Complete flag
+* - USART_FLAG_RXNE: Receive data register not empty flag
+* - USART_FLAG_IDLE: Idle Line detection flag
+* - USART_FLAG_ORE: OverRun Error flag
+* - USART_FLAG_NE: Noise Error flag
+* - USART_FLAG_FE: Framing Error flag
+* - USART_FLAG_PE: Parity Error flag
+* Output : None
+* Return : The new state of USART_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, u16 USART_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_FLAG(USART_FLAG));
+ assert_param(IS_USART_PERIPH_FLAG(USARTx, USART_FLAG)); /* The CTS flag is not available for UART4 and UART5 */
+
+ if ((USARTx->SR & USART_FLAG) != (u16)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : USART_ClearFlag
+* Description : Clears the USARTx's pending flags.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_FLAG: specifies the flag to clear.
+* This parameter can be any combination of the following values:
+* - USART_FLAG_CTS: CTS Change flag (not available for
+* UART4 and UART5).
+* - USART_FLAG_LBD: LIN Break detection flag.
+* - USART_FLAG_TC: Transmission Complete flag.
+* - USART_FLAG_RXNE: Receive data register not empty flag.
+* - USART_FLAG_IDLE: Idle Line detection flag.
+* - USART_FLAG_ORE: OverRun Error flag.
+* - USART_FLAG_NE: Noise Error flag.
+* - USART_FLAG_FE: Framing Error flag.
+* - USART_FLAG_PE: Parity Error flag.
+*
+* Note: - For IDLE, ORE, NE, FE and PE flags user has to read
+* the USART DR register after calling this function.
+* - TXE flag can't be cleared by this function, it's
+* cleared only by a write to the USART DR register.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_ClearFlag(USART_TypeDef* USARTx, u16 USART_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_CLEAR_FLAG(USART_FLAG));
+ assert_param(IS_USART_PERIPH_FLAG(USARTx, USART_FLAG)); /* The CTS flag is not available for UART4 and UART5 */
+
+ USARTx->SR = (u16)~USART_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : USART_GetITStatus
+* Description : Checks whether the specified USART interrupt has occurred or not.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_IT: specifies the USART interrupt source to check.
+* This parameter can be one of the following values:
+* - USART_IT_CTS: CTS change interrupt (not available for
+* UART4 and UART5)
+* - USART_IT_LBD: LIN Break detection interrupt
+* - USART_IT_TXE: Tansmit Data Register empty interrupt
+* - USART_IT_TC: Transmission complete interrupt
+* - USART_IT_RXNE: Receive Data register not empty
+* interrupt
+* - USART_IT_IDLE: Idle line detection interrupt
+* - USART_IT_ORE: OverRun Error interrupt
+* - USART_IT_NE: Noise Error interrupt
+* - USART_IT_FE: Framing Error interrupt
+* - USART_IT_PE: Parity Error interrupt
+* Output : None
+* Return : The new state of USART_IT (SET or RESET).
+*******************************************************************************/
+ITStatus USART_GetITStatus(USART_TypeDef* USARTx, u16 USART_IT)
+{
+ u32 bitpos = 0x00, itmask = 0x00, usartreg = 0x00;
+ ITStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_IT(USART_IT));
+ assert_param(IS_USART_PERIPH_IT(USARTx, USART_IT)); /* The CTS interrupt is not available for UART4 and UART5 */
+
+ /* Get the USART register index */
+ usartreg = (((u8)USART_IT) >> 0x05);
+
+ /* Get the interrupt position */
+ itmask = USART_IT & IT_Mask;
+
+ itmask = (u32)0x01 << itmask;
+
+ if (usartreg == 0x01) /* The IT is in CR1 register */
+ {
+ itmask &= USARTx->CR1;
+ }
+ else if (usartreg == 0x02) /* The IT is in CR2 register */
+ {
+ itmask &= USARTx->CR2;
+ }
+ else /* The IT is in CR3 register */
+ {
+ itmask &= USARTx->CR3;
+ }
+
+ bitpos = USART_IT >> 0x08;
+
+ bitpos = (u32)0x01 << bitpos;
+ bitpos &= USARTx->SR;
+
+ if ((itmask != (u16)RESET)&&(bitpos != (u16)RESET))
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : USART_ClearITPendingBit
+* Description : Clears the USARTx’s interrupt pending bits.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_IT: specifies the interrupt pending bit to clear.
+* This parameter can be one of the following values:
+* - USART_IT_CTS: CTS change interrupt (not available for
+* UART4 and UART5)
+* - USART_IT_LBD: LIN Break detection interrupt
+* - USART_IT_TC: Transmission complete interrupt.
+* - USART_IT_RXNE: Receive Data register not empty interrupt.
+* - USART_IT_IDLE: Idle line detection interrupt.
+* - USART_IT_ORE: OverRun Error interrupt.
+* - USART_IT_NE: Noise Error interrupt.
+* - USART_IT_FE: Framing Error interrupt.
+* - USART_IT_PE: Parity Error interrupt.
+*
+* Note: - For IDLE, ORE, NE, FE and PE pending bits user has to
+* read the USART DR register after calling this function.
+* - TXE pending bit can't be cleared by this function, it's
+* cleared only by a write to the USART DR register.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_ClearITPendingBit(USART_TypeDef* USARTx, u16 USART_IT)
+{
+ u16 bitpos = 0x00, itmask = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_CLEAR_IT(USART_IT));
+ assert_param(IS_USART_PERIPH_IT(USARTx, USART_IT)); /* The CTS interrupt is not available for UART4 and UART5 */
+
+ bitpos = USART_IT >> 0x08;
+
+ itmask = (u16)((u16)0x01 << bitpos);
+ USARTx->SR = (u16)~itmask;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_vector.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_vector.c new file mode 100755 index 0000000..92932c1 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_vector.c @@ -0,0 +1,217 @@ +/******************** (C) COPYRIGHT 2007 STMicroelectronics ********************
+* File Name : stm32f10x_vector.c
+* Author : MCD Application Team
+* Version : V1.0
+* Date : 10/08/2007
+* Description : This file contains the vector table for STM32F10x.
+* After Reset the Cortex-M3 processor is in Thread mode,
+* priority is Privileged, and the Stack is set to Main.
+********************************************************************************
+* THE PRESENT SOFTWARE 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 SOFTWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
+* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMAChannel1_IRQHandler(void);
+void DMAChannel2_IRQHandler(void);
+void DMAChannel3_IRQHandler(void);
+void DMAChannel4_IRQHandler(void);
+void DMAChannel5_IRQHandler(void);
+void DMAChannel6_IRQHandler(void);
+void DMAChannel7_IRQHandler(void);
+void ADC_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+extern unsigned long _etext;
+extern unsigned long _sidata; /* start address for the initialization values
+ of the .data section. defined in linker script */
+extern unsigned long _sdata; /* start address for the .data section. defined
+ in linker script */
+extern unsigned long _edata; /* end address for the .data section. defined in
+ linker script */
+
+extern unsigned long _sbss; /* start address for the .bss section. defined
+ in linker script */
+extern unsigned long _ebss; /* end address for the .bss section. defined in
+ linker script */
+
+extern void _estack; /* init value for the stack pointer. defined in linker script */
+
+
+
+/* Private typedef -----------------------------------------------------------*/
+/* function prototypes -------------------------------------------------------*/
+void Reset_Handler(void) __attribute__((__interrupt__));
+extern int main(void);
+
+
+/*******************************************************************************
+*
+* 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.
+*
+*******************************************************************************/
+
+
+__attribute__ ((section(".isr_vector")))
+void (* const g_pfnVectors[])(void) =
+{
+ &_estack, // The initial stack pointer
+ Reset_Handler, // The reset handler
+ NMIException,
+ HardFaultException,
+ MemManageException,
+ BusFaultException,
+ UsageFaultException,
+ 0, 0, 0, 0, /* Reserved */
+ SVCHandler,
+ DebugMonitor,
+ 0, /* Reserved */
+ PendSVC,
+ SysTickHandler,
+ WWDG_IRQHandler,
+ PVD_IRQHandler,
+ TAMPER_IRQHandler,
+ RTC_IRQHandler,
+ FLASH_IRQHandler,
+ RCC_IRQHandler,
+ EXTI0_IRQHandler,
+ EXTI1_IRQHandler,
+ EXTI2_IRQHandler,
+ EXTI3_IRQHandler,
+ EXTI4_IRQHandler,
+ DMAChannel1_IRQHandler,
+ DMAChannel2_IRQHandler,
+ DMAChannel3_IRQHandler,
+ DMAChannel4_IRQHandler,
+ DMAChannel5_IRQHandler,
+ DMAChannel6_IRQHandler,
+ DMAChannel7_IRQHandler,
+ ADC_IRQHandler,
+ USB_HP_CAN_TX_IRQHandler,
+ USB_LP_CAN_RX0_IRQHandler,
+ CAN_RX1_IRQHandler,
+ CAN_SCE_IRQHandler,
+ EXTI9_5_IRQHandler,
+ TIM1_BRK_IRQHandler,
+ TIM1_UP_IRQHandler,
+ TIM1_TRG_COM_IRQHandler,
+ TIM1_CC_IRQHandler,
+ TIM2_IRQHandler,
+ TIM3_IRQHandler,
+ TIM4_IRQHandler,
+ I2C1_EV_IRQHandler,
+ I2C1_ER_IRQHandler,
+ I2C2_EV_IRQHandler,
+ I2C2_ER_IRQHandler,
+ SPI1_IRQHandler,
+ SPI2_IRQHandler,
+ USART1_IRQHandler,
+ USART2_IRQHandler,
+ USART3_IRQHandler,
+ EXTI15_10_IRQHandler,
+ RTCAlarm_IRQHandler,
+ USBWakeUp_IRQHandler,
+ 0,
+ 0,
+ 0,
+ 0,
+ 0,
+ 0,
+ 0,
+ (unsigned short)0xF108F85F //this is a workaround for boot in RAM mode.
+};
+
+/*******************************************************************************
+* Function Name : Reset_Handler
+* Description : 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.
+* Input :
+* Output :
+* Return :
+*******************************************************************************/
+void Reset_Handler(void)
+{
+ unsigned long *pulSrc, *pulDest;
+
+ //
+ // Copy the data segment initializers from flash to SRAM.
+ //
+ pulSrc = &_sidata;
+ for(pulDest = &_sdata; pulDest < &_edata; )
+ {
+ *(pulDest++) = *(pulSrc++);
+ }
+
+ //
+ // Zero fill the bss segment.
+ //
+ for(pulDest = &_sbss; pulDest < &_ebss; )
+ {
+ *(pulDest++) = 0;
+ }
+
+ //
+ // Call the application's entry point.
+ //
+ main();
+}
+
+
+/****************** (C) COPYRIGHT 2007 STMicroelectronics *****END OF FILE****/
+
+
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_wwdg.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_wwdg.c new file mode 100755 index 0000000..176300e --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/src/stm32f10x_wwdg.c @@ -0,0 +1,190 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_wwdg.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the WWDG firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_wwdg.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ----------- WWDG registers bit address in the alias region ----------- */
+#define WWDG_OFFSET (WWDG_BASE - PERIPH_BASE)
+
+/* Alias word address of EWI bit */
+#define CFR_OFFSET (WWDG_OFFSET + 0x04)
+#define EWI_BitNumber 0x09
+#define CFR_EWI_BB (PERIPH_BB_BASE + (CFR_OFFSET * 32) + (EWI_BitNumber * 4))
+
+/* Alias word address of EWIF bit */
+#define SR_OFFSET (WWDG_OFFSET + 0x08)
+#define EWIF_BitNumber 0x00
+#define SR_EWIF_BB (PERIPH_BB_BASE + (SR_OFFSET * 32) + (EWIF_BitNumber * 4))
+
+/* --------------------- WWDG registers bit mask ------------------------ */
+/* CR register bit mask */
+#define CR_WDGA_Set ((u32)0x00000080)
+
+/* CFR register bit mask */
+#define CFR_WDGTB_Mask ((u32)0xFFFFFE7F)
+#define CFR_W_Mask ((u32)0xFFFFFF80)
+
+#define BIT_Mask ((u8)0x7F)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : WWDG_DeInit
+* Description : Deinitializes the WWDG peripheral registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_DeInit(void)
+{
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, DISABLE);
+}
+
+/*******************************************************************************
+* Function Name : WWDG_SetPrescaler
+* Description : Sets the WWDG Prescaler.
+* Input : - WWDG_Prescaler: specifies the WWDG Prescaler.
+* This parameter can be one of the following values:
+* - WWDG_Prescaler_1: WWDG counter clock = (PCLK1/4096)/1
+* - WWDG_Prescaler_2: WWDG counter clock = (PCLK1/4096)/2
+* - WWDG_Prescaler_4: WWDG counter clock = (PCLK1/4096)/4
+* - WWDG_Prescaler_8: WWDG counter clock = (PCLK1/4096)/8
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_SetPrescaler(u32 WWDG_Prescaler)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_WWDG_PRESCALER(WWDG_Prescaler));
+
+ /* Clear WDGTB[1:0] bits */
+ tmpreg = WWDG->CFR & CFR_WDGTB_Mask;
+
+ /* Set WDGTB[1:0] bits according to WWDG_Prescaler value */
+ tmpreg |= WWDG_Prescaler;
+
+ /* Store the new value */
+ WWDG->CFR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : WWDG_SetWindowValue
+* Description : Sets the WWDG window value.
+* Input : - WindowValue: specifies the window value to be compared to
+* the downcounter.
+* This parameter value must be lower than 0x80.
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_SetWindowValue(u8 WindowValue)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_WWDG_WINDOW_VALUE(WindowValue));
+
+ /* Clear W[6:0] bits */
+ tmpreg = WWDG->CFR & CFR_W_Mask;
+
+ /* Set W[6:0] bits according to WindowValue value */
+ tmpreg |= WindowValue & BIT_Mask;
+
+ /* Store the new value */
+ WWDG->CFR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : WWDG_EnableIT
+* Description : Enables the WWDG Early Wakeup interrupt(EWI).
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_EnableIT(void)
+{
+ *(vu32 *) CFR_EWI_BB = (u32)ENABLE;
+}
+
+/*******************************************************************************
+* Function Name : WWDG_SetCounter
+* Description : Sets the WWDG counter value.
+* Input : - Counter: specifies the watchdog counter value.
+* This parameter must be a number between 0x40 and 0x7F.
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_SetCounter(u8 Counter)
+{
+ /* Check the parameters */
+ assert_param(IS_WWDG_COUNTER(Counter));
+
+ /* Write to T[6:0] bits to configure the counter value, no need to do
+ a read-modify-write; writing a 0 to WDGA bit does nothing */
+ WWDG->CR = Counter & BIT_Mask;
+}
+
+/*******************************************************************************
+* Function Name : WWDG_Enable
+* Description : Enables WWDG and load the counter value.
+* - Counter: specifies the watchdog counter value.
+* This parameter must be a number between 0x40 and 0x7F.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_Enable(u8 Counter)
+{
+ /* Check the parameters */
+ assert_param(IS_WWDG_COUNTER(Counter));
+
+ WWDG->CR = CR_WDGA_Set | Counter;
+}
+
+/*******************************************************************************
+* Function Name : WWDG_GetFlagStatus
+* Description : Checks whether the Early Wakeup interrupt flag is set or not.
+* Input : None
+* Output : None
+* Return : The new state of the Early Wakeup interrupt flag (SET or RESET)
+*******************************************************************************/
+FlagStatus WWDG_GetFlagStatus(void)
+{
+ return (FlagStatus)(*(vu32 *) SR_EWIF_BB);
+}
+
+/*******************************************************************************
+* Function Name : WWDG_ClearFlag
+* Description : Clears Early Wakeup interrupt flag.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_ClearFlag(void)
+{
+ WWDG->SR = (u32)RESET;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/version-ld.txt b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/version-ld.txt new file mode 100755 index 0000000..4a68bef --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/version-ld.txt @@ -0,0 +1 @@ +Linker scripts taken from RAISONANCE RKitARM for RIDE7 1.03.0004.
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/version-lib.txt b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/version-lib.txt new file mode 100755 index 0000000..cb8ecc9 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/lib/version-lib.txt @@ -0,0 +1,105 @@ +/******************** (C) COPYRIGHT 2007 STMicroelectronics ********************
+* File Name : version.txt
+* Author : MCD Application Team
+* Version : V1.0
+* Date : 10/08/2007
+* Description : Version file for STM32F10x Firmware Library.
+********************************************************************************
+* THE PRESENT SOFTWARE 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 SOFTWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
+* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+*******************************************************************************/
+
+* V1.0 - 10/08/2007
+====================
+ + Add template project with RIDE toolchain
+
+ + In all stm32f10x_ppp.c and stm32f10x_conf.h files: change "assert" macro name
+ to "assert_param"
+ Note: If you are using the FW Library V0.3 in your application and you want to
+ migrate to V1.0, you have to update your application’s “stm32f10x_conf.h”
+ file with the latest one (provided with V1.0).
+
+ + stm32f10x_conf.h
+ - Remove '#undef assert'
+ - Change '#define DEBUG' by '#define DEBUG 1'
+
+ + stm32f10x_type.h
+ - Add new types: sc32, sc16, sc8, vsc32, vsc16 and vsc8
+
+ + stm32f10x_it.c
+ - Add basic fault exception handling: in "HardFaultException", "MemManageException",
+ "BusFaultException" and "UsageFaultException" ISR the following code was added:
+ /* Go to infinite loop when exception occurs */
+ while (1)
+ {
+ }
+
+ + stm32f10x_rcc.c
+ - "RCC_WaitForHSEStartUp()" function updated to resolve issue with high GNU
+ compiler optimization
+
+ + stm32f10x_gpio.h
+ - '#define GPIO_Remap1_CAN ((u32)0x001D2000)' changed to
+ '#define GPIO_Remap1_CAN ((u32)0x001D4000)'
+
+ + stm32f10x_rtc.c/.h
+ - "RTC_GetPrescaler" function removed
+
+ + stm32f10x_bkp.c/.h
+ - add "BKP_RTCOutputConfig()" function to allow to select the RTC output
+ source(Calib clock, RTC Alarm or RTC Second) to output on Tamper pin and
+ remove "BKP_RTCCalibrationClockOutputCmd()" function
+
+ + stm32f10x_can.h
+ - CAN synchronization jump width defines updated
+ - '#define CAN_SJW_0tq' ==> '#define CAN_SJW_1tq'
+ - '#define CAN_SJW_1tq' ==> '#define CAN_SJW_2tq'
+ - '#define CAN_SJW_2tq' ==> '#define CAN_SJW_3tq'
+ - '#define CAN_SJW_3tq' ==> '#define CAN_SJW_4tq'
+
+ + stm32f10x_tim1.c/.h
+ - "TIM1_OCxNPolarityConfig(u16 TIM1_OCPolarity)" function: change parameter
+ name to 'TIM1_OCNPolarity'
+ - change 'TIM1_ICSelection_TRGI' by 'TIM1_ICSelection_TRC'
+
+ + stm32f10x_tim.c/.h
+ - change 'TIM_ICSelection_TRGI' by 'TIM_ICSelection_TRC'
+
+ + examples
+ - ADC examples 3 & 4 updated
+ - DEBUG example
+ - Example modified to support RIDE specific printf function implementation
+ - I2C example5
+ - i2c_ee.c: add the following function prototypes: "void GPIO_Configuration(void)"
+ add "void I2C_Configuration(void)"
+ - Add GPIO pin toggle example
+ - BKP, CAN, DMA, NVIC and I2C examples readme files updated
+ - Use decimal (instead of hexadecimal) values constants in TIM, TIM1 and
+ IWDG examples
+ - USART
+ - example 12
+ - USART3 ISR updated
+ - Timeout define "SC_Receive_Timeout" updated to 0x4000
+ - example 7
+ - Example modified to support RIDE specific printf function implementation
+ - RTC example
+ - Example modified to support RIDE specific printf function implementation
+ - Change "BKP_RTCCalibrationClockOutputCmd()" function by "RTC_ClockOutput()"
+ - LSI removed as RTC clock source
+ - IWDG example
+ - LSI frequency value changed from 32 KHz to 40 KHz
+ - Update the STM32F10x evaluation board name from STM32F10x-EVAL to STM3210B-EVAL
+
+
+* V0.3 - 05/21/2007
+====================
+ Created.
+
+
+******************* (C) COPYRIGHT 2007 STMicroelectronics *****END OF FILE******
+
+
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main Binary files differnew file mode 100755 index 0000000..81098cb --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.bin b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.bin new file mode 100755 index 0000000..e69de29 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.bin diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.c new file mode 100755 index 0000000..8502183 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.c @@ -0,0 +1,204 @@ +/******************** (C) COPYRIGHT 2007 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V1.0
+* Date : 10/08/2007
+* Description : Main program body
+********************************************************************************
+* THE PRESENT SOFTWARE 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 SOFTWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
+* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+GPIO_InitTypeDef GPIO_InitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+void Delay(vu32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* Configure the system clocks */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* Enable GPIOC clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);
+
+ /* Configure PC.12 as Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+
+ /* Bit Banged PWM Handler Vars*/
+ int thresh = 128;
+ int count = 0;
+ vu32 fadeRateCount = 0;
+ const vu32 fadeRate = 0xFFFF;
+
+ while (1)
+ {
+ /* Main Pwm Handling for a given thresh */
+ if (count < thresh)
+ {
+ GPIO_SetBits(GPIOC,GPIO_Pin_12);
+ } else
+ {
+ GPIO_ResetBits(GPIOC,GPIO_Pin_12);
+ }
+
+ count++;
+
+ if (count == 255)
+ {
+ fadeRateCount++;
+
+ if (fadeRateCount == fadeRate)
+ {
+ thresh += 5;
+ fadeRateCount = 0;
+ }
+ }
+
+ /* Insert delay */
+ Delay(0xAFFFF);
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for(; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2007 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.elf b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.elf Binary files differnew file mode 100755 index 0000000..b9de87a --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.elf diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.elf.map b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.elf.map new file mode 100755 index 0000000..689b327 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.elf.map @@ -0,0 +1,675 @@ +Archive member included because of file (symbol)
+
+lib/libstm32.a(stm32f10x_flash.o)
+ main.o (FLASH_SetLatency)
+lib/libstm32.a(stm32f10x_gpio.o)
+ main.o (GPIO_Init)
+lib/libstm32.a(stm32f10x_nvic.o)
+ main.o (NVIC_SetVectorTable)
+lib/libstm32.a(stm32f10x_rcc.o)
+ main.o (RCC_DeInit)
+
+Allocating common symbols
+Common symbol size file
+
+HSEStartUpStatus 0x1 main.o
+GPIO_InitStructure 0x4 main.o
+
+Discarded input sections
+
+ .text 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .data 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .bss 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .init 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .fini 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .text 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .data 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .bss 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .init_array 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .fini_array 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .eh_frame 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .jcr 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .text 0x00000000 0x0 main.o
+ .data 0x00000000 0x0 main.o
+ .bss 0x00000000 0x0 main.o
+ COMMON 0x00000000 0x0 main.o
+ .text 0x00000000 0x0 stm32f10x_it.o
+ .data 0x00000000 0x0 stm32f10x_it.o
+ .bss 0x00000000 0x0 stm32f10x_it.o
+ .text 0x00000000 0x0 lib/libstm32.a(stm32f10x_flash.o)
+ .data 0x00000000 0x0 lib/libstm32.a(stm32f10x_flash.o)
+ .bss 0x00000000 0x0 lib/libstm32.a(stm32f10x_flash.o)
+ .text 0x00000000 0x0 lib/libstm32.a(stm32f10x_gpio.o)
+ .data 0x00000000 0x0 lib/libstm32.a(stm32f10x_gpio.o)
+ .bss 0x00000000 0x0 lib/libstm32.a(stm32f10x_gpio.o)
+ .text 0x00000000 0x0 lib/libstm32.a(stm32f10x_nvic.o)
+ .data 0x00000000 0x0 lib/libstm32.a(stm32f10x_nvic.o)
+ .bss 0x00000000 0x0 lib/libstm32.a(stm32f10x_nvic.o)
+ .text 0x00000000 0x0 lib/libstm32.a(stm32f10x_rcc.o)
+ .data 0x00000000 0x0 lib/libstm32.a(stm32f10x_rcc.o)
+ .bss 0x00000000 0x0 lib/libstm32.a(stm32f10x_rcc.o)
+ .rodata 0x00000000 0x0 lib/libstm32.a(stm32f10x_rcc.o)
+ .text 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .data 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .bss 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .eh_frame 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .jcr 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .text 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+ .data 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+ .bss 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+ .init 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+ .fini 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+
+Memory Configuration
+
+Name Origin Length Attributes
+RAM 0x20000000 0x00005000 xrw
+FLASH 0x08000000 0x00020000 xr
+FLASHB1 0x00000000 0x00000000 xr
+EXTMEMB0 0x00000000 0x00000000 xr
+EXTMEMB1 0x00000000 0x00000000 xr
+EXTMEMB2 0x00000000 0x00000000 xr
+EXTMEMB3 0x00000000 0x00000000 xr
+*default* 0x00000000 0xffffffff
+
+Linker script and memory map
+
+LOAD c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+LOAD c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+LOAD main.o
+LOAD stm32f10x_it.o
+LOAD lib/libstm32.a
+START GROUP
+LOAD c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3\libgcc.a
+LOAD c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/../../../../arm-none-eabi/lib\libc.a
+END GROUP
+LOAD c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+LOAD c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+ 0x00000400 __Stack_Size = 0x400
+ 0x00000400 PROVIDE (_Stack_Size, __Stack_Size)
+ 0x20004c00 __Stack_Init = (_estack - __Stack_Size)
+ 0x20004c00 PROVIDE (_Stack_Init, __Stack_Init)
+ 0x00000100 _Minimum_Stack_Size = 0x100
+ 0x00000000 PROVIDE (Undefined_Handler, 0x0)
+ 0x00000000 PROVIDE (SWI_Handler, 0x0)
+ 0x00000000 PROVIDE (IRQ_Handler, 0x0)
+ 0x00000000 PROVIDE (Prefetch_Handler, 0x0)
+ 0x00000000 PROVIDE (Abort_Handler, 0x0)
+ 0x00000000 PROVIDE (FIQ_Handler, 0x0)
+ 0x00000000 PROVIDE (NMIException, 0x0)
+ 0x00000000 PROVIDE (HardFaultException, 0x0)
+ 0x00000000 PROVIDE (MemManageException, 0x0)
+ 0x00000000 PROVIDE (BusFaultException, 0x0)
+ 0x00000000 PROVIDE (UsageFaultException, 0x0)
+ 0x00000000 PROVIDE (SVCHandler, 0x0)
+ 0x00000000 PROVIDE (DebugMonitor, 0x0)
+ 0x00000000 PROVIDE (PendSVC, 0x0)
+ 0x00000000 PROVIDE (SysTickHandler, 0x0)
+ 0x00000000 PROVIDE (WWDG_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (PVD_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TAMPER_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (RTC_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (FLASH_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (RCC_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (EXTI0_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (EXTI1_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (EXTI2_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (EXTI3_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (EXTI4_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (DMAChannel1_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (DMAChannel2_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (DMAChannel3_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (DMAChannel4_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (DMAChannel5_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (DMAChannel6_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (DMAChannel7_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (ADC_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (USB_HP_CAN_TX_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (USB_LP_CAN_RX0_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (CAN_RX1_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (CAN_SCE_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (EXTI9_5_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TIM1_BRK_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TIM1_UP_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TIM1_TRG_COM_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TIM1_CC_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TIM2_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TIM3_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TIM4_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (I2C1_EV_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (I2C1_ER_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (I2C2_EV_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (I2C2_ER_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (SPI1_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (SPI2_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (USART1_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (USART2_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (USART3_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (EXTI15_10_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (RTCAlarm_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (USBWakeUp_IRQHandler, 0x0)
+ 0x42000000 PERIPH_BB_BASE = 0x42000000
+ 0x22000000 SRAM_BB_BASE = 0x22000000
+ 0x20000000 SRAM_BASE = 0x20000000
+ 0x40000000 PERIPH_BASE = 0x40000000
+ 0x40022000 PROVIDE (FLASH_BASE, 0x40022000)
+ 0x1ffff800 PROVIDE (OB_BASE, 0x1ffff800)
+ 0x40000000 APB1PERIPH_BASE = PERIPH_BASE
+ 0x40010000 APB2PERIPH_BASE = (PERIPH_BASE + 0x10000)
+ 0x40020000 AHBPERIPH_BASE = (PERIPH_BASE + 0x20000)
+ 0x40000000 PROVIDE (TIM2, (APB1PERIPH_BASE + 0x0))
+ 0x40000400 PROVIDE (TIM3, (APB1PERIPH_BASE + 0x400))
+ 0x40000800 PROVIDE (TIM4, (APB1PERIPH_BASE + 0x800))
+ 0x40002800 PROVIDE (RTC, (APB1PERIPH_BASE + 0x2800))
+ 0x40002c00 PROVIDE (WWDG, (APB1PERIPH_BASE + 0x2c00))
+ 0x40003000 PROVIDE (IWDG, (APB1PERIPH_BASE + 0x3000))
+ 0x40003800 PROVIDE (SPI2, (APB1PERIPH_BASE + 0x3800))
+ 0x40004400 PROVIDE (USART2, (APB1PERIPH_BASE + 0x4400))
+ 0x40004800 PROVIDE (USART3, (APB1PERIPH_BASE + 0x4800))
+ 0x40005400 PROVIDE (I2C1, (APB1PERIPH_BASE + 0x5400))
+ 0x40005800 PROVIDE (I2C2, (APB1PERIPH_BASE + 0x5800))
+ 0x40006400 PROVIDE (CAN, (APB1PERIPH_BASE + 0x6400))
+ 0x40006c00 PROVIDE (BKP, (APB1PERIPH_BASE + 0x6c00))
+ 0x40007000 PROVIDE (PWR, (APB1PERIPH_BASE + 0x7000))
+ 0x40010000 PROVIDE (AFIO, (APB2PERIPH_BASE + 0x0))
+ 0x40010400 PROVIDE (EXTI, (APB2PERIPH_BASE + 0x400))
+ 0x40010800 PROVIDE (GPIOA, (APB2PERIPH_BASE + 0x800))
+ 0x40010c00 PROVIDE (GPIOB, (APB2PERIPH_BASE + 0xc00))
+ 0x40011000 PROVIDE (GPIOC, (APB2PERIPH_BASE + 0x1000))
+ 0x40011400 PROVIDE (GPIOD, (APB2PERIPH_BASE + 0x1400))
+ 0x40011800 PROVIDE (GPIOE, (APB2PERIPH_BASE + 0x1800))
+ 0x40012400 PROVIDE (ADC1, (APB2PERIPH_BASE + 0x2400))
+ 0x40012800 PROVIDE (ADC2, (APB2PERIPH_BASE + 0x2800))
+ 0x40012c00 PROVIDE (TIM1, (APB2PERIPH_BASE + 0x2c00))
+ 0x40013000 PROVIDE (SPI1, (APB2PERIPH_BASE + 0x3000))
+ 0x40013800 PROVIDE (USART1, (APB2PERIPH_BASE + 0x3800))
+ 0x40020000 PROVIDE (DMA, (AHBPERIPH_BASE + 0x0))
+ 0x40020008 PROVIDE (DMA_Channel1, (AHBPERIPH_BASE + 0x8))
+ 0x4002001c PROVIDE (DMA_Channel2, (AHBPERIPH_BASE + 0x1c))
+ 0x40020030 PROVIDE (DMA_Channel3, (AHBPERIPH_BASE + 0x30))
+ 0x40020044 PROVIDE (DMA_Channel4, (AHBPERIPH_BASE + 0x44))
+ 0x40020058 PROVIDE (DMA_Channel5, (AHBPERIPH_BASE + 0x58))
+ 0x4002006c PROVIDE (DMA_Channel6, (AHBPERIPH_BASE + 0x6c))
+ 0x40020080 PROVIDE (DMA_Channel7, (AHBPERIPH_BASE + 0x80))
+ 0x40021000 PROVIDE (RCC, (AHBPERIPH_BASE + 0x1000))
+ 0xe000e000 SCS_BASE = 0xe000e000
+ 0xe000e010 PROVIDE (SysTick, (SCS_BASE + 0x10))
+ 0xe000e100 PROVIDE (NVIC, (SCS_BASE + 0x100))
+ 0xe000ed00 PROVIDE (SCB, (SCS_BASE + 0xd00))
+ 0x20005000 _estack = 0x20005000
+
+.isr_vector 0x08000000 0x0
+ 0x08000000 . = ALIGN (0x4)
+ *(.isr_vector)
+ 0x08000000 . = ALIGN (0x4)
+
+.flashtext 0x08000000 0x0
+ 0x08000000 . = ALIGN (0x4)
+ *(.flashtext)
+ 0x08000000 . = ALIGN (0x4)
+
+.text 0x08000000 0x0
+ 0x08000000 . = ALIGN (0x4)
+ *(.text)
+ *(.text.*)
+ *(.rodata)
+ *(.rodata*)
+ *(.glue_7)
+ .glue_7 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .glue_7 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .glue_7 0x08000000 0x0 main.o
+ .glue_7 0x08000000 0x0 stm32f10x_it.o
+ .glue_7 0x08000000 0x0 lib/libstm32.a(stm32f10x_flash.o)
+ .glue_7 0x08000000 0x0 lib/libstm32.a(stm32f10x_gpio.o)
+ .glue_7 0x08000000 0x0 lib/libstm32.a(stm32f10x_nvic.o)
+ .glue_7 0x08000000 0x0 lib/libstm32.a(stm32f10x_rcc.o)
+ .glue_7 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .glue_7 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+ *(.glue_7t)
+ .glue_7t 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .glue_7t 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .glue_7t 0x08000000 0x0 main.o
+ .glue_7t 0x08000000 0x0 stm32f10x_it.o
+ .glue_7t 0x08000000 0x0 lib/libstm32.a(stm32f10x_flash.o)
+ .glue_7t 0x08000000 0x0 lib/libstm32.a(stm32f10x_gpio.o)
+ .glue_7t 0x08000000 0x0 lib/libstm32.a(stm32f10x_nvic.o)
+ .glue_7t 0x08000000 0x0 lib/libstm32.a(stm32f10x_rcc.o)
+ .glue_7t 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .glue_7t 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+ 0x08000000 . = ALIGN (0x4)
+ 0x08000000 _etext = .
+ 0x08000000 _sidata = _etext
+
+.vfp11_veneer 0x20000000 0x0
+ .vfp11_veneer 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .vfp11_veneer 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .vfp11_veneer 0x20000000 0x0 main.o
+ .vfp11_veneer 0x20000000 0x0 stm32f10x_it.o
+ .vfp11_veneer 0x20000000 0x0 lib/libstm32.a(stm32f10x_flash.o)
+ .vfp11_veneer 0x20000000 0x0 lib/libstm32.a(stm32f10x_gpio.o)
+ .vfp11_veneer 0x20000000 0x0 lib/libstm32.a(stm32f10x_nvic.o)
+ .vfp11_veneer 0x20000000 0x0 lib/libstm32.a(stm32f10x_rcc.o)
+ .vfp11_veneer 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .vfp11_veneer 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+
+.v4_bx 0x20000000 0x0
+ .v4_bx 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .v4_bx 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .v4_bx 0x20000000 0x0 main.o
+ .v4_bx 0x20000000 0x0 stm32f10x_it.o
+ .v4_bx 0x20000000 0x0 lib/libstm32.a(stm32f10x_flash.o)
+ .v4_bx 0x20000000 0x0 lib/libstm32.a(stm32f10x_gpio.o)
+ .v4_bx 0x20000000 0x0 lib/libstm32.a(stm32f10x_nvic.o)
+ .v4_bx 0x20000000 0x0 lib/libstm32.a(stm32f10x_rcc.o)
+ .v4_bx 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .v4_bx 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+
+.data 0x20000000 0x0 load address 0x08000000
+ 0x20000000 . = ALIGN (0x4)
+ 0x20000000 _sdata = .
+ *(.data)
+ *(.data.*)
+ 0x20000000 . = ALIGN (0x4)
+ 0x20000000 _edata = .
+
+.bss 0x20000000 0x0
+ 0x20000000 . = ALIGN (0x4)
+ 0x20000000 _sbss = .
+ *(.bss)
+ *(COMMON)
+ 0x20000000 . = ALIGN (0x4)
+ 0x20000000 _ebss = .
+ 0x20000000 PROVIDE (end, _ebss)
+ 0x20000000 PROVIDE (_end, _ebss)
+
+._usrstack 0x20000000 0x100
+ 0x20000000 . = ALIGN (0x4)
+ 0x20000000 _susrstack = .
+ 0x20000100 . = (. + _Minimum_Stack_Size)
+ *fill* 0x20000000 0x100 00
+ 0x20000100 . = ALIGN (0x4)
+ 0x20000100 _eusrstack = .
+
+.b1text
+ *(.b1text)
+ *(.b1rodata)
+ *(.b1rodata*)
+
+.eb0text
+ *(.eb0text)
+ *(.eb0rodata)
+ *(.eb0rodata*)
+
+.eb1text
+ *(.eb1text)
+ *(.eb1rodata)
+ *(.eb1rodata*)
+
+.eb2text
+ *(.eb2text)
+ *(.eb2rodata)
+ *(.eb2rodata*)
+
+.eb3text
+ *(.eb3text)
+ *(.eb3rodata)
+ *(.eb3rodata*)
+ 0x20000100 __exidx_start = .
+ 0x20000100 __exidx_end = .
+
+/DISCARD/
+ libc.a(*)
+ libm.a(*)
+ libgcc.a(*)
+
+.stab
+ *(.stab)
+
+.stabstr
+ *(.stabstr)
+
+.stab.excl
+ *(.stab.excl)
+
+.stab.exclstr
+ *(.stab.exclstr)
+
+.stab.index
+ *(.stab.index)
+
+.stab.indexstr
+ *(.stab.indexstr)
+
+.comment 0x00000000 0x102
+ *(.comment)
+ .comment 0x00000000 0x2b main.o
+ .comment 0x0000002b 0x2b stm32f10x_it.o
+ .comment 0x00000056 0x2b lib/libstm32.a(stm32f10x_flash.o)
+ .comment 0x00000081 0x2b lib/libstm32.a(stm32f10x_gpio.o)
+ .comment 0x000000ac 0x2b lib/libstm32.a(stm32f10x_nvic.o)
+ .comment 0x000000d7 0x2b lib/libstm32.a(stm32f10x_rcc.o)
+
+.debug
+ *(.debug)
+
+.line
+ *(.line)
+
+.debug_srcinfo
+ *(.debug_srcinfo)
+
+.debug_sfnames
+ *(.debug_sfnames)
+
+.debug_aranges 0x00000000 0xc0
+ *(.debug_aranges)
+ .debug_aranges
+ 0x00000000 0x20 main.o
+ .debug_aranges
+ 0x00000020 0x20 stm32f10x_it.o
+ .debug_aranges
+ 0x00000040 0x20 lib/libstm32.a(stm32f10x_flash.o)
+ .debug_aranges
+ 0x00000060 0x20 lib/libstm32.a(stm32f10x_gpio.o)
+ .debug_aranges
+ 0x00000080 0x20 lib/libstm32.a(stm32f10x_nvic.o)
+ .debug_aranges
+ 0x000000a0 0x20 lib/libstm32.a(stm32f10x_rcc.o)
+
+.debug_pubnames
+ 0x00000000 0xeb9
+ *(.debug_pubnames)
+ .debug_pubnames
+ 0x00000000 0x7e main.o
+ .debug_pubnames
+ 0x0000007e 0x63c stm32f10x_it.o
+ .debug_pubnames
+ 0x000006ba 0x60 lib/libstm32.a(stm32f10x_flash.o)
+ .debug_pubnames
+ 0x0000071a 0x17b lib/libstm32.a(stm32f10x_gpio.o)
+ .debug_pubnames
+ 0x00000895 0x360 lib/libstm32.a(stm32f10x_nvic.o)
+ .debug_pubnames
+ 0x00000bf5 0x2c4 lib/libstm32.a(stm32f10x_rcc.o)
+
+.debug_info 0x00000000 0x344e
+ *(.debug_info .gnu.linkonce.wi.*)
+ .debug_info 0x00000000 0x45e main.o
+ .debug_info 0x0000045e 0xac7 stm32f10x_it.o
+ .debug_info 0x00000f25 0x275 lib/libstm32.a(stm32f10x_flash.o)
+ .debug_info 0x0000119a 0x918 lib/libstm32.a(stm32f10x_gpio.o)
+ .debug_info 0x00001ab2 0xd65 lib/libstm32.a(stm32f10x_nvic.o)
+ .debug_info 0x00002817 0xc37 lib/libstm32.a(stm32f10x_rcc.o)
+
+.debug_abbrev 0x00000000 0x74a
+ *(.debug_abbrev)
+ .debug_abbrev 0x00000000 0x105 main.o
+ .debug_abbrev 0x00000105 0x52 stm32f10x_it.o
+ .debug_abbrev 0x00000157 0x93 lib/libstm32.a(stm32f10x_flash.o)
+ .debug_abbrev 0x000001ea 0x1b4 lib/libstm32.a(stm32f10x_gpio.o)
+ .debug_abbrev 0x0000039e 0x1f6 lib/libstm32.a(stm32f10x_nvic.o)
+ .debug_abbrev 0x00000594 0x1b6 lib/libstm32.a(stm32f10x_rcc.o)
+
+.debug_line 0x00000000 0x6fb
+ *(.debug_line)
+ .debug_line 0x00000000 0xab main.o
+ .debug_line 0x000000ab 0x14f stm32f10x_it.o
+ .debug_line 0x000001fa 0x88 lib/libstm32.a(stm32f10x_flash.o)
+ .debug_line 0x00000282 0x14c lib/libstm32.a(stm32f10x_gpio.o)
+ .debug_line 0x000003ce 0x195 lib/libstm32.a(stm32f10x_nvic.o)
+ .debug_line 0x00000563 0x198 lib/libstm32.a(stm32f10x_rcc.o)
+
+.debug_frame 0x00000000 0x1034
+ *(.debug_frame)
+ .debug_frame 0x00000000 0x84 main.o
+ .debug_frame 0x00000084 0x688 stm32f10x_it.o
+ .debug_frame 0x0000070c 0x64 lib/libstm32.a(stm32f10x_flash.o)
+ .debug_frame 0x00000770 0x1f4 lib/libstm32.a(stm32f10x_gpio.o)
+ .debug_frame 0x00000964 0x348 lib/libstm32.a(stm32f10x_nvic.o)
+ .debug_frame 0x00000cac 0x388 lib/libstm32.a(stm32f10x_rcc.o)
+
+.debug_str 0x00000000 0xfb
+ *(.debug_str)
+ .debug_str 0x00000000 0x58 lib/libstm32.a(stm32f10x_gpio.o)
+ .debug_str 0x00000058 0x5b lib/libstm32.a(stm32f10x_nvic.o)
+ .debug_str 0x000000b3 0x48 lib/libstm32.a(stm32f10x_rcc.o)
+
+.debug_loc 0x00000000 0x1d51
+ *(.debug_loc)
+ .debug_loc 0x00000000 0xc4 main.o
+ .debug_loc 0x000000c4 0xb97 stm32f10x_it.o
+ .debug_loc 0x00000c5b 0xa5 lib/libstm32.a(stm32f10x_flash.o)
+ .debug_loc 0x00000d00 0x39b lib/libstm32.a(stm32f10x_gpio.o)
+ .debug_loc 0x0000109b 0x5fa lib/libstm32.a(stm32f10x_nvic.o)
+ .debug_loc 0x00001695 0x6bc lib/libstm32.a(stm32f10x_rcc.o)
+
+.debug_macinfo
+ *(.debug_macinfo)
+
+.debug_weaknames
+ *(.debug_weaknames)
+
+.debug_funcnames
+ *(.debug_funcnames)
+
+.debug_typenames
+ *(.debug_typenames)
+
+.debug_varnames
+ *(.debug_varnames)
+OUTPUT(main.elf elf32-littlearm)
+
+.ARM.attributes
+ 0x00000000 0x31
+ .ARM.attributes
+ 0x00000000 0x14 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .ARM.attributes
+ 0x00000014 0x2e c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .ARM.attributes
+ 0x00000042 0x31 main.o
+ .ARM.attributes
+ 0x00000073 0x31 stm32f10x_it.o
+ .ARM.attributes
+ 0x000000a4 0x31 lib/libstm32.a(stm32f10x_flash.o)
+ .ARM.attributes
+ 0x000000d5 0x31 lib/libstm32.a(stm32f10x_gpio.o)
+ .ARM.attributes
+ 0x00000106 0x31 lib/libstm32.a(stm32f10x_nvic.o)
+ .ARM.attributes
+ 0x00000137 0x31 lib/libstm32.a(stm32f10x_rcc.o)
+ .ARM.attributes
+ 0x00000168 0x2c c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .ARM.attributes
+ 0x00000194 0x14 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+
+Cross Reference Table
+
+Symbol File
+ADC1_2_IRQHandler stm32f10x_it.o
+ADC3_IRQHandler stm32f10x_it.o
+BusFaultException stm32f10x_it.o
+CAN_RX1_IRQHandler stm32f10x_it.o
+CAN_SCE_IRQHandler stm32f10x_it.o
+DMA1_Channel1_IRQHandler stm32f10x_it.o
+DMA1_Channel2_IRQHandler stm32f10x_it.o
+DMA1_Channel3_IRQHandler stm32f10x_it.o
+DMA1_Channel4_IRQHandler stm32f10x_it.o
+DMA1_Channel5_IRQHandler stm32f10x_it.o
+DMA1_Channel6_IRQHandler stm32f10x_it.o
+DMA1_Channel7_IRQHandler stm32f10x_it.o
+DMA2_Channel1_IRQHandler stm32f10x_it.o
+DMA2_Channel2_IRQHandler stm32f10x_it.o
+DMA2_Channel3_IRQHandler stm32f10x_it.o
+DMA2_Channel4_5_IRQHandler stm32f10x_it.o
+DebugMonitor stm32f10x_it.o
+Delay main.o
+EXTI0_IRQHandler stm32f10x_it.o
+EXTI15_10_IRQHandler stm32f10x_it.o
+EXTI1_IRQHandler stm32f10x_it.o
+EXTI2_IRQHandler stm32f10x_it.o
+EXTI3_IRQHandler stm32f10x_it.o
+EXTI4_IRQHandler stm32f10x_it.o
+EXTI9_5_IRQHandler stm32f10x_it.o
+FLASH_HalfCycleAccessCmd lib/libstm32.a(stm32f10x_flash.o)
+FLASH_IRQHandler stm32f10x_it.o
+FLASH_PrefetchBufferCmd lib/libstm32.a(stm32f10x_flash.o)
+ main.o
+FLASH_SetLatency lib/libstm32.a(stm32f10x_flash.o)
+ main.o
+FSMC_IRQHandler stm32f10x_it.o
+GPIO_AFIODeInit lib/libstm32.a(stm32f10x_gpio.o)
+GPIO_DeInit lib/libstm32.a(stm32f10x_gpio.o)
+GPIO_EXTILineConfig lib/libstm32.a(stm32f10x_gpio.o)
+GPIO_EventOutputCmd lib/libstm32.a(stm32f10x_gpio.o)
+GPIO_EventOutputConfig lib/libstm32.a(stm32f10x_gpio.o)
+GPIO_Init lib/libstm32.a(stm32f10x_gpio.o)
+ main.o
+GPIO_InitStructure main.o
+GPIO_PinLockConfig lib/libstm32.a(stm32f10x_gpio.o)
+GPIO_PinRemapConfig lib/libstm32.a(stm32f10x_gpio.o)
+GPIO_ReadInputData lib/libstm32.a(stm32f10x_gpio.o)
+GPIO_ReadInputDataBit lib/libstm32.a(stm32f10x_gpio.o)
+GPIO_ReadOutputData lib/libstm32.a(stm32f10x_gpio.o)
+GPIO_ReadOutputDataBit lib/libstm32.a(stm32f10x_gpio.o)
+GPIO_ResetBits lib/libstm32.a(stm32f10x_gpio.o)
+ main.o
+GPIO_SetBits lib/libstm32.a(stm32f10x_gpio.o)
+ main.o
+GPIO_StructInit lib/libstm32.a(stm32f10x_gpio.o)
+GPIO_Write lib/libstm32.a(stm32f10x_gpio.o)
+GPIO_WriteBit lib/libstm32.a(stm32f10x_gpio.o)
+HSEStartUpStatus main.o
+HardFaultException stm32f10x_it.o
+I2C1_ER_IRQHandler stm32f10x_it.o
+I2C1_EV_IRQHandler stm32f10x_it.o
+I2C2_ER_IRQHandler stm32f10x_it.o
+I2C2_EV_IRQHandler stm32f10x_it.o
+MemManageException stm32f10x_it.o
+NMIException stm32f10x_it.o
+NVIC_BASEPRICONFIG lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_ClearIRQChannelPendingBit lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_ClearSystemHandlerPendingBit lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_Configuration main.o
+NVIC_DeInit lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_GenerateCoreReset lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_GenerateSystemReset lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_GetBASEPRI lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_GetCPUID lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_GetCurrentActiveHandler lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_GetCurrentPendingIRQChannel lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_GetFaultAddress lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_GetFaultHandlerSources lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_GetIRQChannelActiveBitStatus lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_GetIRQChannelPendingBitStatus lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_GetSystemHandlerActiveBitStatus lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_GetSystemHandlerPendingBitStatus lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_Init lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_PriorityGroupConfig lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_RESETFAULTMASK lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_RESETPRIMASK lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_SCBDeInit lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_SETFAULTMASK lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_SETPRIMASK lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_SetIRQChannelPendingBit lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_SetSystemHandlerPendingBit lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_SetVectorTable lib/libstm32.a(stm32f10x_nvic.o)
+ main.o
+NVIC_StructInit lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_SystemHandlerConfig lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_SystemHandlerPriorityConfig lib/libstm32.a(stm32f10x_nvic.o)
+NVIC_SystemLPConfig lib/libstm32.a(stm32f10x_nvic.o)
+PVD_IRQHandler stm32f10x_it.o
+PendSVC stm32f10x_it.o
+RCC_ADCCLKConfig lib/libstm32.a(stm32f10x_rcc.o)
+RCC_AHBPeriphClockCmd lib/libstm32.a(stm32f10x_rcc.o)
+RCC_APB1PeriphClockCmd lib/libstm32.a(stm32f10x_rcc.o)
+RCC_APB1PeriphResetCmd lib/libstm32.a(stm32f10x_rcc.o)
+RCC_APB2PeriphClockCmd lib/libstm32.a(stm32f10x_rcc.o)
+ main.o
+RCC_APB2PeriphResetCmd lib/libstm32.a(stm32f10x_rcc.o)
+ lib/libstm32.a(stm32f10x_gpio.o)
+RCC_AdjustHSICalibrationValue lib/libstm32.a(stm32f10x_rcc.o)
+RCC_BackupResetCmd lib/libstm32.a(stm32f10x_rcc.o)
+RCC_ClearFlag lib/libstm32.a(stm32f10x_rcc.o)
+RCC_ClearITPendingBit lib/libstm32.a(stm32f10x_rcc.o)
+RCC_ClockSecuritySystemCmd lib/libstm32.a(stm32f10x_rcc.o)
+RCC_Configuration main.o
+RCC_DeInit lib/libstm32.a(stm32f10x_rcc.o)
+ main.o
+RCC_GetClocksFreq lib/libstm32.a(stm32f10x_rcc.o)
+RCC_GetFlagStatus lib/libstm32.a(stm32f10x_rcc.o)
+ main.o
+RCC_GetITStatus lib/libstm32.a(stm32f10x_rcc.o)
+RCC_GetSYSCLKSource lib/libstm32.a(stm32f10x_rcc.o)
+ main.o
+RCC_HCLKConfig lib/libstm32.a(stm32f10x_rcc.o)
+ main.o
+RCC_HSEConfig lib/libstm32.a(stm32f10x_rcc.o)
+ main.o
+RCC_HSICmd lib/libstm32.a(stm32f10x_rcc.o)
+RCC_IRQHandler stm32f10x_it.o
+RCC_ITConfig lib/libstm32.a(stm32f10x_rcc.o)
+RCC_LSEConfig lib/libstm32.a(stm32f10x_rcc.o)
+RCC_LSICmd lib/libstm32.a(stm32f10x_rcc.o)
+RCC_MCOConfig lib/libstm32.a(stm32f10x_rcc.o)
+RCC_PCLK1Config lib/libstm32.a(stm32f10x_rcc.o)
+ main.o
+RCC_PCLK2Config lib/libstm32.a(stm32f10x_rcc.o)
+ main.o
+RCC_PLLCmd lib/libstm32.a(stm32f10x_rcc.o)
+ main.o
+RCC_PLLConfig lib/libstm32.a(stm32f10x_rcc.o)
+ main.o
+RCC_RTCCLKCmd lib/libstm32.a(stm32f10x_rcc.o)
+RCC_RTCCLKConfig lib/libstm32.a(stm32f10x_rcc.o)
+RCC_SYSCLKConfig lib/libstm32.a(stm32f10x_rcc.o)
+ main.o
+RCC_USBCLKConfig lib/libstm32.a(stm32f10x_rcc.o)
+RCC_WaitForHSEStartUp lib/libstm32.a(stm32f10x_rcc.o)
+ main.o
+RTCAlarm_IRQHandler stm32f10x_it.o
+RTC_IRQHandler stm32f10x_it.o
+SDIO_IRQHandler stm32f10x_it.o
+SPI1_IRQHandler stm32f10x_it.o
+SPI2_IRQHandler stm32f10x_it.o
+SPI3_IRQHandler stm32f10x_it.o
+SVCHandler stm32f10x_it.o
+SysTickHandler stm32f10x_it.o
+TAMPER_IRQHandler stm32f10x_it.o
+TIM1_BRK_IRQHandler stm32f10x_it.o
+TIM1_CC_IRQHandler stm32f10x_it.o
+TIM1_TRG_COM_IRQHandler stm32f10x_it.o
+TIM1_UP_IRQHandler stm32f10x_it.o
+TIM2_IRQHandler stm32f10x_it.o
+TIM3_IRQHandler stm32f10x_it.o
+TIM4_IRQHandler stm32f10x_it.o
+TIM5_IRQHandler stm32f10x_it.o
+TIM6_IRQHandler stm32f10x_it.o
+TIM7_IRQHandler stm32f10x_it.o
+TIM8_BRK_IRQHandler stm32f10x_it.o
+TIM8_CC_IRQHandler stm32f10x_it.o
+TIM8_TRG_COM_IRQHandler stm32f10x_it.o
+TIM8_UP_IRQHandler stm32f10x_it.o
+UART4_IRQHandler stm32f10x_it.o
+UART5_IRQHandler stm32f10x_it.o
+USART1_IRQHandler stm32f10x_it.o
+USART2_IRQHandler stm32f10x_it.o
+USART3_IRQHandler stm32f10x_it.o
+USBWakeUp_IRQHandler stm32f10x_it.o
+USB_HP_CAN_TX_IRQHandler stm32f10x_it.o
+USB_LP_CAN_RX0_IRQHandler stm32f10x_it.o
+UsageFaultException stm32f10x_it.o
+WWDG_IRQHandler stm32f10x_it.o
+_Jv_RegisterClasses c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+__BASEPRICONFIG lib/libstm32.a(stm32f10x_nvic.o)
+__GetBASEPRI lib/libstm32.a(stm32f10x_nvic.o)
+__RESETFAULTMASK lib/libstm32.a(stm32f10x_nvic.o)
+__RESETPRIMASK lib/libstm32.a(stm32f10x_nvic.o)
+__SETFAULTMASK lib/libstm32.a(stm32f10x_nvic.o)
+__SETPRIMASK lib/libstm32.a(stm32f10x_nvic.o)
+__deregister_frame_info c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+__dso_handle c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+__register_frame_info c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+_fini c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+_init c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+main main.o
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.map b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.map new file mode 100755 index 0000000..4b73523 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/main.map @@ -0,0 +1,406 @@ +
+Allocating common symbols
+Common symbol size file
+
+HSEStartUpStatus 0x1 main.o
+GPIO_InitStructure 0x4 main.o
+
+Discarded input sections
+
+ .text 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .data 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .bss 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .init 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .fini 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .text 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .data 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .bss 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .init_array 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .fini_array 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .eh_frame 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .jcr 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .text 0x00000000 0x0 main.o
+ .data 0x00000000 0x0 main.o
+ .bss 0x00000000 0x0 main.o
+ COMMON 0x00000000 0x0 main.o
+ .text 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .data 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .bss 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .eh_frame 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .jcr 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .text 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+ .data 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+ .bss 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+ .init 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+ .fini 0x00000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+
+Memory Configuration
+
+Name Origin Length Attributes
+RAM 0x20000000 0x00005000 xrw
+FLASH 0x08000000 0x00020000 xr
+FLASHB1 0x00000000 0x00000000 xr
+EXTMEMB0 0x00000000 0x00000000 xr
+EXTMEMB1 0x00000000 0x00000000 xr
+EXTMEMB2 0x00000000 0x00000000 xr
+EXTMEMB3 0x00000000 0x00000000 xr
+*default* 0x00000000 0xffffffff
+
+Linker script and memory map
+
+LOAD c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+LOAD c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+LOAD main.o
+START GROUP
+LOAD c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3\libgcc.a
+LOAD c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/../../../../arm-none-eabi/lib\libc.a
+END GROUP
+LOAD c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+LOAD c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+ 0x00000400 __Stack_Size = 0x400
+ 0x00000400 PROVIDE (_Stack_Size, __Stack_Size)
+ 0x20004c00 __Stack_Init = (_estack - __Stack_Size)
+ 0x20004c00 PROVIDE (_Stack_Init, __Stack_Init)
+ 0x00000100 _Minimum_Stack_Size = 0x100
+ 0x00000000 PROVIDE (Undefined_Handler, 0x0)
+ 0x00000000 PROVIDE (SWI_Handler, 0x0)
+ 0x00000000 PROVIDE (IRQ_Handler, 0x0)
+ 0x00000000 PROVIDE (Prefetch_Handler, 0x0)
+ 0x00000000 PROVIDE (Abort_Handler, 0x0)
+ 0x00000000 PROVIDE (FIQ_Handler, 0x0)
+ 0x00000000 PROVIDE (NMIException, 0x0)
+ 0x00000000 PROVIDE (HardFaultException, 0x0)
+ 0x00000000 PROVIDE (MemManageException, 0x0)
+ 0x00000000 PROVIDE (BusFaultException, 0x0)
+ 0x00000000 PROVIDE (UsageFaultException, 0x0)
+ 0x00000000 PROVIDE (SVCHandler, 0x0)
+ 0x00000000 PROVIDE (DebugMonitor, 0x0)
+ 0x00000000 PROVIDE (PendSVC, 0x0)
+ 0x00000000 PROVIDE (SysTickHandler, 0x0)
+ 0x00000000 PROVIDE (WWDG_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (PVD_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TAMPER_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (RTC_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (FLASH_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (RCC_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (EXTI0_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (EXTI1_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (EXTI2_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (EXTI3_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (EXTI4_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (DMAChannel1_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (DMAChannel2_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (DMAChannel3_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (DMAChannel4_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (DMAChannel5_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (DMAChannel6_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (DMAChannel7_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (ADC_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (USB_HP_CAN_TX_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (USB_LP_CAN_RX0_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (CAN_RX1_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (CAN_SCE_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (EXTI9_5_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TIM1_BRK_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TIM1_UP_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TIM1_TRG_COM_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TIM1_CC_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TIM2_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TIM3_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (TIM4_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (I2C1_EV_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (I2C1_ER_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (I2C2_EV_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (I2C2_ER_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (SPI1_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (SPI2_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (USART1_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (USART2_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (USART3_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (EXTI15_10_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (RTCAlarm_IRQHandler, 0x0)
+ 0x00000000 PROVIDE (USBWakeUp_IRQHandler, 0x0)
+ 0x42000000 PERIPH_BB_BASE = 0x42000000
+ 0x22000000 SRAM_BB_BASE = 0x22000000
+ 0x20000000 SRAM_BASE = 0x20000000
+ 0x40000000 PERIPH_BASE = 0x40000000
+ 0x40022000 PROVIDE (FLASH_BASE, 0x40022000)
+ 0x1ffff800 PROVIDE (OB_BASE, 0x1ffff800)
+ 0x40000000 APB1PERIPH_BASE = PERIPH_BASE
+ 0x40010000 APB2PERIPH_BASE = (PERIPH_BASE + 0x10000)
+ 0x40020000 AHBPERIPH_BASE = (PERIPH_BASE + 0x20000)
+ 0x40000000 PROVIDE (TIM2, (APB1PERIPH_BASE + 0x0))
+ 0x40000400 PROVIDE (TIM3, (APB1PERIPH_BASE + 0x400))
+ 0x40000800 PROVIDE (TIM4, (APB1PERIPH_BASE + 0x800))
+ 0x40002800 PROVIDE (RTC, (APB1PERIPH_BASE + 0x2800))
+ 0x40002c00 PROVIDE (WWDG, (APB1PERIPH_BASE + 0x2c00))
+ 0x40003000 PROVIDE (IWDG, (APB1PERIPH_BASE + 0x3000))
+ 0x40003800 PROVIDE (SPI2, (APB1PERIPH_BASE + 0x3800))
+ 0x40004400 PROVIDE (USART2, (APB1PERIPH_BASE + 0x4400))
+ 0x40004800 PROVIDE (USART3, (APB1PERIPH_BASE + 0x4800))
+ 0x40005400 PROVIDE (I2C1, (APB1PERIPH_BASE + 0x5400))
+ 0x40005800 PROVIDE (I2C2, (APB1PERIPH_BASE + 0x5800))
+ 0x40006400 PROVIDE (CAN, (APB1PERIPH_BASE + 0x6400))
+ 0x40006c00 PROVIDE (BKP, (APB1PERIPH_BASE + 0x6c00))
+ 0x40007000 PROVIDE (PWR, (APB1PERIPH_BASE + 0x7000))
+ 0x40010000 PROVIDE (AFIO, (APB2PERIPH_BASE + 0x0))
+ 0x40010400 PROVIDE (EXTI, (APB2PERIPH_BASE + 0x400))
+ 0x40010800 PROVIDE (GPIOA, (APB2PERIPH_BASE + 0x800))
+ 0x40010c00 PROVIDE (GPIOB, (APB2PERIPH_BASE + 0xc00))
+ 0x40011000 PROVIDE (GPIOC, (APB2PERIPH_BASE + 0x1000))
+ 0x40011400 PROVIDE (GPIOD, (APB2PERIPH_BASE + 0x1400))
+ 0x40011800 PROVIDE (GPIOE, (APB2PERIPH_BASE + 0x1800))
+ 0x40012400 PROVIDE (ADC1, (APB2PERIPH_BASE + 0x2400))
+ 0x40012800 PROVIDE (ADC2, (APB2PERIPH_BASE + 0x2800))
+ 0x40012c00 PROVIDE (TIM1, (APB2PERIPH_BASE + 0x2c00))
+ 0x40013000 PROVIDE (SPI1, (APB2PERIPH_BASE + 0x3000))
+ 0x40013800 PROVIDE (USART1, (APB2PERIPH_BASE + 0x3800))
+ 0x40020000 PROVIDE (DMA, (AHBPERIPH_BASE + 0x0))
+ 0x40020008 PROVIDE (DMA_Channel1, (AHBPERIPH_BASE + 0x8))
+ 0x4002001c PROVIDE (DMA_Channel2, (AHBPERIPH_BASE + 0x1c))
+ 0x40020030 PROVIDE (DMA_Channel3, (AHBPERIPH_BASE + 0x30))
+ 0x40020044 PROVIDE (DMA_Channel4, (AHBPERIPH_BASE + 0x44))
+ 0x40020058 PROVIDE (DMA_Channel5, (AHBPERIPH_BASE + 0x58))
+ 0x4002006c PROVIDE (DMA_Channel6, (AHBPERIPH_BASE + 0x6c))
+ 0x40020080 PROVIDE (DMA_Channel7, (AHBPERIPH_BASE + 0x80))
+ 0x40021000 PROVIDE (RCC, (AHBPERIPH_BASE + 0x1000))
+ 0xe000e000 SCS_BASE = 0xe000e000
+ 0xe000e010 PROVIDE (SysTick, (SCS_BASE + 0x10))
+ 0xe000e100 PROVIDE (NVIC, (SCS_BASE + 0x100))
+ 0xe000ed00 PROVIDE (SCB, (SCS_BASE + 0xd00))
+ 0x20005000 _estack = 0x20005000
+
+.isr_vector 0x08000000 0x0
+ 0x08000000 . = ALIGN (0x4)
+ *(.isr_vector)
+ 0x08000000 . = ALIGN (0x4)
+
+.flashtext 0x08000000 0x0
+ 0x08000000 . = ALIGN (0x4)
+ *(.flashtext)
+ 0x08000000 . = ALIGN (0x4)
+
+.text 0x08000000 0x0
+ 0x08000000 . = ALIGN (0x4)
+ *(.text)
+ *(.text.*)
+ *(.rodata)
+ *(.rodata*)
+ *(.glue_7)
+ .glue_7 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .glue_7 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .glue_7 0x08000000 0x0 main.o
+ .glue_7 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .glue_7 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+ *(.glue_7t)
+ .glue_7t 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .glue_7t 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .glue_7t 0x08000000 0x0 main.o
+ .glue_7t 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .glue_7t 0x08000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+ 0x08000000 . = ALIGN (0x4)
+ 0x08000000 _etext = .
+ 0x08000000 _sidata = _etext
+
+.vfp11_veneer 0x20000000 0x0
+ .vfp11_veneer 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .vfp11_veneer 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .vfp11_veneer 0x20000000 0x0 main.o
+ .vfp11_veneer 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .vfp11_veneer 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+
+.v4_bx 0x20000000 0x0
+ .v4_bx 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .v4_bx 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .v4_bx 0x20000000 0x0 main.o
+ .v4_bx 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .v4_bx 0x20000000 0x0 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+
+.data 0x20000000 0x0 load address 0x08000000
+ 0x20000000 . = ALIGN (0x4)
+ 0x20000000 _sdata = .
+ *(.data)
+ *(.data.*)
+ 0x20000000 . = ALIGN (0x4)
+ 0x20000000 _edata = .
+
+.bss 0x20000000 0x0
+ 0x20000000 . = ALIGN (0x4)
+ 0x20000000 _sbss = .
+ *(.bss)
+ *(COMMON)
+ 0x20000000 . = ALIGN (0x4)
+ 0x20000000 _ebss = .
+ 0x20000000 PROVIDE (end, _ebss)
+ 0x20000000 PROVIDE (_end, _ebss)
+
+._usrstack 0x20000000 0x100
+ 0x20000000 . = ALIGN (0x4)
+ 0x20000000 _susrstack = .
+ 0x20000100 . = (. + _Minimum_Stack_Size)
+ *fill* 0x20000000 0x100 00
+ 0x20000100 . = ALIGN (0x4)
+ 0x20000100 _eusrstack = .
+
+.b1text
+ *(.b1text)
+ *(.b1rodata)
+ *(.b1rodata*)
+
+.eb0text
+ *(.eb0text)
+ *(.eb0rodata)
+ *(.eb0rodata*)
+
+.eb1text
+ *(.eb1text)
+ *(.eb1rodata)
+ *(.eb1rodata*)
+
+.eb2text
+ *(.eb2text)
+ *(.eb2rodata)
+ *(.eb2rodata*)
+
+.eb3text
+ *(.eb3text)
+ *(.eb3rodata)
+ *(.eb3rodata*)
+ 0x20000100 __exidx_start = .
+ 0x20000100 __exidx_end = .
+
+/DISCARD/
+ libc.a(*)
+ libm.a(*)
+ libgcc.a(*)
+
+.stab
+ *(.stab)
+
+.stabstr
+ *(.stabstr)
+
+.stab.excl
+ *(.stab.excl)
+
+.stab.exclstr
+ *(.stab.exclstr)
+
+.stab.index
+ *(.stab.index)
+
+.stab.indexstr
+ *(.stab.indexstr)
+
+.comment 0x00000000 0x2b
+ *(.comment)
+ .comment 0x00000000 0x2b main.o
+
+.debug
+ *(.debug)
+
+.line
+ *(.line)
+
+.debug_srcinfo
+ *(.debug_srcinfo)
+
+.debug_sfnames
+ *(.debug_sfnames)
+
+.debug_aranges 0x00000000 0x20
+ *(.debug_aranges)
+ .debug_aranges
+ 0x00000000 0x20 main.o
+
+.debug_pubnames
+ 0x00000000 0x7e
+ *(.debug_pubnames)
+ .debug_pubnames
+ 0x00000000 0x7e main.o
+
+.debug_info 0x00000000 0x45e
+ *(.debug_info .gnu.linkonce.wi.*)
+ .debug_info 0x00000000 0x45e main.o
+
+.debug_abbrev 0x00000000 0x105
+ *(.debug_abbrev)
+ .debug_abbrev 0x00000000 0x105 main.o
+
+.debug_line 0x00000000 0xab
+ *(.debug_line)
+ .debug_line 0x00000000 0xab main.o
+
+.debug_frame 0x00000000 0x84
+ *(.debug_frame)
+ .debug_frame 0x00000000 0x84 main.o
+
+.debug_str
+ *(.debug_str)
+
+.debug_loc 0x00000000 0xc4
+ *(.debug_loc)
+ .debug_loc 0x00000000 0xc4 main.o
+
+.debug_macinfo
+ *(.debug_macinfo)
+
+.debug_weaknames
+ *(.debug_weaknames)
+
+.debug_funcnames
+ *(.debug_funcnames)
+
+.debug_typenames
+ *(.debug_typenames)
+
+.debug_varnames
+ *(.debug_varnames)
+OUTPUT(main elf32-littlearm)
+
+.ARM.attributes
+ 0x00000000 0x31
+ .ARM.attributes
+ 0x00000000 0x14 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+ .ARM.attributes
+ 0x00000014 0x2e c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+ .ARM.attributes
+ 0x00000042 0x31 main.o
+ .ARM.attributes
+ 0x00000073 0x2c c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtend.o
+ .ARM.attributes
+ 0x0000009f 0x14 c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtn.o
+
+Cross Reference Table
+
+Symbol File
+Delay main.o
+FLASH_PrefetchBufferCmd main.o
+FLASH_SetLatency main.o
+GPIO_Init main.o
+GPIO_InitStructure main.o
+GPIO_ResetBits main.o
+GPIO_SetBits main.o
+HSEStartUpStatus main.o
+NVIC_Configuration main.o
+NVIC_SetVectorTable main.o
+RCC_APB2PeriphClockCmd main.o
+RCC_Configuration main.o
+RCC_DeInit main.o
+RCC_GetFlagStatus main.o
+RCC_GetSYSCLKSource main.o
+RCC_HCLKConfig main.o
+RCC_HSEConfig main.o
+RCC_PCLK1Config main.o
+RCC_PCLK2Config main.o
+RCC_PLLCmd main.o
+RCC_PLLConfig main.o
+RCC_SYSCLKConfig main.o
+RCC_WaitForHSEStartUp main.o
+_Jv_RegisterClasses c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+__deregister_frame_info c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+__dso_handle c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+__register_frame_info c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crtbegin.o
+_fini c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+_init c:/program files/codesourcery/sourcery g++ lite/bin/../lib/gcc/arm-none-eabi/4.2.3/crti.o
+main main.o
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/mainBkup.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/mainBkup.c new file mode 100755 index 0000000..936a09f --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/mainBkup.c @@ -0,0 +1,265 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define DAC_DHR12RD_Address 0x40007420
+
+/* Init Structure definition */
+DAC_InitTypeDef DAC_InitStructure;
+DMA_InitTypeDef DMA_InitStructure;
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+uc16 Sine12bit[32] = {2047, 2447, 2831, 3185, 3498, 3750, 3939, 4056, 4095, 4056,
+ 3939, 3750, 3495, 3185, 2831, 2447, 2047, 1647, 1263, 909,
+ 599, 344, 155, 38, 0, 38, 155, 344, 599, 909, 1263, 1647};
+
+u32 DualSine12bit[32];
+u8 Idx = 0;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+void Delay(vu32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* GPIO configuration */
+ GPIO_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* TIM8 Configuration */
+ /* Time base configuration */
+ TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
+ TIM_TimeBaseStructure.TIM_Period = 0x19;
+ TIM_TimeBaseStructure.TIM_Prescaler = 0x0;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0x0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseInit(TIM8, &TIM_TimeBaseStructure);
+
+ /* TIM8 TRGO selection */
+ TIM_SelectOutputTrigger(TIM8, TIM_TRGOSource_Update);
+
+ /* DAC channel1 Configuration */
+ DAC_InitStructure.DAC_Trigger = DAC_Trigger_T8_TRGO;
+ DAC_InitStructure.DAC_WaveGeneration = DAC_WaveGeneration_None;
+ DAC_InitStructure.DAC_OutputBuffer = DAC_OutputBuffer_Disable;
+ DAC_Init(DAC_Channel_1, &DAC_InitStructure);
+
+ /* DAC channel2 Configuration */
+ DAC_Init(DAC_Channel_2, &DAC_InitStructure);
+
+ /* Fill Sine32bit table */
+ for (Idx= 0; Idx<32; Idx++)
+ {
+ DualSine12bit[Idx] = (Sine12bit[Idx] << 16) + (Sine12bit[Idx]);
+ }
+
+ /* DMA2 channel4 configuration */
+ DMA_DeInit(DMA2_Channel4);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = DAC_DHR12RD_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)&DualSine12bit;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
+ DMA_InitStructure.DMA_BufferSize = 32;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA2_Channel4, &DMA_InitStructure);
+
+ /* Enable DMA2 Channel4 */
+ DMA_Cmd(DMA2_Channel4, ENABLE);
+
+ /* Enable DAC Channel1 */
+ DAC_Cmd(DAC_Channel_1, ENABLE);
+ /* Enable DAC Channel2 */
+ DAC_Cmd(DAC_Channel_2, ENABLE);
+
+ /* Enable DMA for DAC Channel2 */
+ DAC_DMACmd(DAC_Channel_2, ENABLE);
+
+ /* TIM8 enable counter */
+ TIM_Cmd(TIM8, ENABLE);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* DMA clock enable */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA2, ENABLE);
+ /* AFIO and GPIOA Periph clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOA, ENABLE);
+ /* DAC Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_DAC, ENABLE);
+ /* TIM8 Periph clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure DAC channe1 and DAC channel2 outputs pins */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 | GPIO_Pin_5;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for(; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/makefile b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/makefile new file mode 100755 index 0000000..ec9fcd6 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/makefile @@ -0,0 +1,85 @@ +# setup
+
+COMPILE_OPTS = -mcpu=cortex-m3 -mthumb -Wall -g -O0
+INCLUDE_DIRS = -I . -I lib/inc
+LIBRARY_DIRS = -L lib
+
+CC = arm-none-eabi-gcc
+CFLAGS = $(COMPILE_OPTS) $(INCLUDE_DIRS)
+
+CXX = arm-none-eabi-g++
+CXXFLAGS = $(COMPILE_OPTS) $(INCLUDE_DIRS)
+
+AS = arm-none-eabi-gcc
+ASFLAGS = $(COMPILE_OPTS) -c
+
+LD = arm-none-eabi-gcc
+LDFLAGS = -Wl,--gc-sections,-Map=$@.map,-cref,-u,Reset_Handler $(INCLUDE_DIRS) $(LIBRARY_DIRS) -T stm32.ld
+
+OBJCP = arm-none-eabi-objcopy
+OBJCPFLAGS = -O binary
+
+AR = arm-none-eabi-ar
+ARFLAGS = cr
+
+MAIN_OUT = main
+MAIN_OUT_ELF = $(MAIN_OUT).elf
+MAIN_OUT_BIN = $(MAIN_OUT).bin
+
+# all
+
+all: $(MAIN_OUT_ELF) $(MAIN_OUT_BIN)
+
+# main
+
+$(MAIN_OUT_ELF): main.o stm32f10x_it.o lib/libstm32.a
+ $(LD) $(LDFLAGS) main.o stm32f10x_it.o lib/libstm32.a --output $@
+
+$(MAIN_OUT_BIN): $(MAIN_OUT_ELF)
+ $(OBJCP) $(OBJCPFLAGS) $< $@
+
+
+# flash
+
+# this is key, copy the .elf file under a new name into the jtag dir
+# run openocd, and load the chip all in one step.
+flash: $(MAIN_OUT)
+ @cp $(MAIN_OUT_ELF) jtag/flash
+ @cd jtag; openocd -f flash.cfg
+# @rm jtag/flash
+
+
+# libstm32.a
+
+LIBSTM32_OUT = lib/libstm32.a
+
+LIBSTM32_OBJS = \
+ lib/src/stm32f10x_adc.o \
+ lib/src/stm32f10x_bkp.o \
+ lib/src/stm32f10x_can.o \
+ lib/src/stm32f10x_dac.o \
+ lib/src/stm32f10x_dma.o \
+ lib/src/stm32f10x_exti.o \
+ lib/src/stm32f10x_flash.o \
+ lib/src/stm32f10x_gpio.o \
+ lib/src/stm32f10x_i2c.o \
+ lib/src/stm32f10x_iwdg.o \
+ lib/src/stm32f10x_lib.o \
+ lib/src/stm32f10x_nvic.o \
+ lib/src/stm32f10x_pwr.o \
+ lib/src/stm32f10x_rcc.o \
+ lib/src/stm32f10x_rtc.o \
+ lib/src/stm32f10x_spi.o \
+ lib/src/stm32f10x_systick.o \
+ lib/src/stm32f10x_tim.o \
+ lib/src/stm32f10x_usart.o \
+ lib/src/stm32f10x_wwdg.o
+
+$(LIBSTM32_OUT): $(LIBSTM32_OBJS)
+ $(AR) $(ARFLAGS) $@ $(LIBSTM32_OBJS)
+
+$(LIBSTM32_OBJS): stm32f10x_conf.h
+
+
+clean:
+ -rm *.o lib/src/*.o $(LIBSTM32_OUT) $(MAIN_OUT_ELF) $(MAIN_OUT_BIN)
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/readme.txt b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/readme.txt new file mode 100755 index 0000000..f369047 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/readme.txt @@ -0,0 +1,69 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the DAC dual mode sine wave example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example describes how to use DAC dual channel mode with DMA to generate sine
+waves on both DAC channels outpouts.
+
+Both DAC channels conversions are configured to be triggered by TIM8 TRGO triggers
+and without noise/triangle wave generation. 12bit right data alignement is selected
+since we choose to acces DAC_DHR12RD register. DMA2 channel4 is configured to
+transfer continuously, word by word, a 32-word buffer to the dual DAC register
+DAC_DHR12RD.
+
+The transfered 32buffer is made to have a sine wave generation on each DAC channel
+output. Both DAC channels are then enabled. Only DAC channel2 DMA capability is enabled.
+
+Once TIM8 is enabled, each TIM8 TRGO update event generate a DMA request which
+transfer data to the dual DAC register and DAC conversion is started. The sine
+waves can be visualized by connecting both PA.04 and PA.05 pins to an oscilloscope.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board and can be
+easily tailored to any other hardware.
+
+ - Connect PA.04 and PA.05 pins to an oscilloscope
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_dac.c
+ + stm32f10x_dma.c
+ + stm32f10x_tim.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/stm32.ld b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/stm32.ld new file mode 100755 index 0000000..5e4ce87 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/stm32.ld @@ -0,0 +1,29 @@ +/*
+Linker script for STM32F10x
+Copyright RAISONANCE 2007 (modified by Lanchon 1-Feb-2008)
+You can use, copy and distribute this file freely, but without any waranty.
+Configure memory sizes, end of stack and boot mode for your project here.
+*/
+
+
+/* include the common STM32F10x sub-script */
+INCLUDE "STM32_COMMON.ld"
+
+/* Memory Spaces Definitions */
+MEMORY
+{
+ RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K /* also change _estack below */
+ FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 128K
+ FLASHB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+ EXTMEMB0 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+ EXTMEMB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+ EXTMEMB2 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+ EXTMEMB3 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+}
+
+/* highest address of the user mode stack */
+_estack = 0x20005000;
+
+/* include the section management sub-script */
+/* (either "STM32_SEC_FLASH.ld" or "STM32_SEC_RAM.ld") */
+INCLUDE "STM32_SEC_FLASH.ld"
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/stm32f10x_conf.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/stm32f10x_conf.h new file mode 100755 index 0000000..1e536c1 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+#define _ADC
+#define _ADC1
+#define _ADC2
+#define _ADC3
+
+/************************************* BKP ************************************/
+#define _BKP
+
+/************************************* CAN ************************************/
+#define _CAN
+
+/************************************* CRC ************************************/
+#define _CRC
+
+/************************************* DAC ************************************/
+#define _DAC
+
+/************************************* DBGMCU *********************************/
+#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+#define _DMA1_Channel1
+#define _DMA1_Channel2
+#define _DMA1_Channel3
+#define _DMA1_Channel4
+#define _DMA1_Channel5
+#define _DMA1_Channel6
+#define _DMA1_Channel7
+#define _DMA2_Channel1
+#define _DMA2_Channel2
+#define _DMA2_Channel3
+#define _DMA2_Channel4
+#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+#define _GPIOD
+#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+#define _I2C
+#define _I2C1
+#define _I2C2
+
+/************************************* IWDG ***********************************/
+#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+#define _RTC
+
+/************************************* SDIO ***********************************/
+#define _SDIO
+
+/************************************* SPI ************************************/
+#define _SPI
+#define _SPI1
+#define _SPI2
+#define _SPI3
+
+/************************************* SysTick ********************************/
+#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+#define _TIM1
+#define _TIM2
+#define _TIM3
+#define _TIM4
+#define _TIM5
+#define _TIM6
+#define _TIM7
+#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+#define _USART1
+#define _USART2
+#define _USART3
+#define _UART4
+#define _UART5
+
+/************************************* WWDG ***********************************/
+#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/stm32f10x_it.c b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/DualModeDMA_SineWave/stm32f10x_it.h b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/DAC/DualModeDMA_SineWave/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/main.c b/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/main.c new file mode 100755 index 0000000..8bd0e49 --- /dev/null +++ b/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/main.c @@ -0,0 +1,242 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define DAC_DHR8R1_Address 0x40007410
+
+/* Init Structure definition */
+DAC_InitTypeDef DAC_InitStructure;
+DMA_InitTypeDef DMA_InitStructure;
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+uc8 Escalator8bit[6] = {0x0, 0x33, 0x66, 0x99, 0xCC, 0xFF};
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+void Delay(vu32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* GPIO configuration */
+ GPIO_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* TIM6 Configuration */
+ TIM_PrescalerConfig(TIM6, 0xF, TIM_PSCReloadMode_Update);
+ TIM_SetAutoreload(TIM6, 0xFF);
+ /* TIM6 TRGO selection */
+ TIM_SelectOutputTrigger(TIM6, TIM_TRGOSource_Update);
+
+ /* DAC channel1 Configuration */
+ DAC_InitStructure.DAC_Trigger = DAC_Trigger_T6_TRGO;
+ DAC_InitStructure.DAC_WaveGeneration = DAC_WaveGeneration_None;
+ DAC_InitStructure.DAC_OutputBuffer = DAC_OutputBuffer_Disable;
+ DAC_Init(DAC_Channel_1, &DAC_InitStructure);
+
+ /* DMA2 channel3 configuration */
+ DMA_DeInit(DMA2_Channel3);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = DAC_DHR8R1_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)&Escalator8bit;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
+ DMA_InitStructure.DMA_BufferSize = 6;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA2_Channel3, &DMA_InitStructure);
+
+ /* Enable DMA2 Channel3 */
+ DMA_Cmd(DMA2_Channel3, ENABLE);
+
+ /* Enable DAC Channel1 */
+ DAC_Cmd(DAC_Channel_1, ENABLE);
+
+ /* Enable DMA for DAC Channel1 */
+ DAC_DMACmd(DAC_Channel_1, ENABLE);
+
+ /* TIM6 enable counter */
+ TIM_Cmd(TIM6, ENABLE);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* DMA clock enable */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA2, ENABLE);
+ /* AFIO and GPIOA Periph clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOA, ENABLE);
+ /* DAC Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_DAC, ENABLE);
+ /* TIM6 Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure DAC channe1 output pin */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for(; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/readme.txt b/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/readme.txt new file mode 100755 index 0000000..d5e132a --- /dev/null +++ b/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/readme.txt @@ -0,0 +1,68 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the DAC one channel DMA escalator example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example describes how to use one DAC channel mode with DMA to generate an
+escalator signal on DAC channel1 outpout.
+
+DAC channel1 conversion is configured to be triggered by TIM6 TRGO triggers and
+without noise/triangle wave generation. 8bit right data alignement is selected
+since we choose to acces DAC_DHR8R1 register.
+DMA2 channel3 is configured to transfer continuously, byte by byte, a 6-byte
+buffer to the DAC1 register DAC_DHR8R1.
+
+The transfered 6bytes buffer is made to have an escalator signal on DAC channel1
+output. DAC channel1 is then enabled. Once TIM6 is enabled, each TIM6 TRGO update
+event generate a DMA request which transfer data to the DAC1 register and DAC
+conversion is started. The escalator signal can be visualized by connecting PA.04
+pin to an oscilloscope.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board and can be
+easily tailored to any other hardware.
+
+ - Connect PA.04 pin to an oscilloscope
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_dac.c
+ + stm32f10x_dma.c
+ + stm32f10x_tim.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/stm32f10x_conf.h b/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/stm32f10x_conf.h new file mode 100755 index 0000000..c5a71e0 --- /dev/null +++ b/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/stm32f10x_it.c b/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/stm32f10x_it.h b/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/DAC/OneChannelDMA_Escalator/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/OneChannel_NoiseWave/main.c b/src/stm32lib/examples/DAC/OneChannel_NoiseWave/main.c new file mode 100755 index 0000000..7e4ea27 --- /dev/null +++ b/src/stm32lib/examples/DAC/OneChannel_NoiseWave/main.c @@ -0,0 +1,210 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Init Structure definition */
+DAC_InitTypeDef DAC_InitStructure;
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+void Delay(vu32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* GPIO configuration */
+ GPIO_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* DAC channel1 Configuration */
+ DAC_InitStructure.DAC_Trigger = DAC_Trigger_Software;
+ DAC_InitStructure.DAC_WaveGeneration = DAC_WaveGeneration_Noise;
+ DAC_InitStructure.DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bits8_0;
+ DAC_InitStructure.DAC_OutputBuffer = DAC_OutputBuffer_Enable;
+ DAC_Init(DAC_Channel_1, &DAC_InitStructure);
+
+ /* Enable DAC Channel1 */
+ DAC_Cmd(DAC_Channel_1, ENABLE);
+
+ /* Set DAC Channel1 DHR12L register */
+ DAC_SetChannel1Data(DAC_Align_12b_L, 0x7FF0);
+
+ while (1)
+ {
+ /* Start DAC Channel1 conversion by software */
+ DAC_SoftwareTriggerCmd(DAC_Channel_1, ENABLE);
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* AFIO and GPIOA Periph clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOA, ENABLE);
+ /* DAC Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_DAC, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure DAC channe1 output pin */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for(; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/OneChannel_NoiseWave/readme.txt b/src/stm32lib/examples/DAC/OneChannel_NoiseWave/readme.txt new file mode 100755 index 0000000..5938e1b --- /dev/null +++ b/src/stm32lib/examples/DAC/OneChannel_NoiseWave/readme.txt @@ -0,0 +1,67 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the DAC one channel noise wave example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example describes how to use one DAC channel to generate a signal with noise
+waves on DAC Channel1 output.
+
+DAC channel1 conversion are configured to be triggered by software with noise wave
+generation.12bit left data alignement is selected since we choose to acces DAC_DHR12L1
+register. Bits 0 to 8 are masked for the Linear feedback shift register.
+DAC channel1 is then enabled. DAC Channel1 DHR12L1 register is configured to have
+an output voltage of VREF/2.
+
+Software triggers are generated continuously in an infinite loop, and on each
+trigger the DAC channel1 start the conversion and calculate the noise value to
+apply on the DAC channel1 output.
+
+The output signal with noise waves can be visualized by connecting PA.04 pin to
+an oscilloscope.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board and can be
+easily tailored to any other hardware.
+
+ - Connect PA.04 pin to an oscilloscope
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_dac.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/DAC/OneChannel_NoiseWave/stm32f10x_conf.h b/src/stm32lib/examples/DAC/OneChannel_NoiseWave/stm32f10x_conf.h new file mode 100755 index 0000000..b2b588f --- /dev/null +++ b/src/stm32lib/examples/DAC/OneChannel_NoiseWave/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/OneChannel_NoiseWave/stm32f10x_it.c b/src/stm32lib/examples/DAC/OneChannel_NoiseWave/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/DAC/OneChannel_NoiseWave/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/OneChannel_NoiseWave/stm32f10x_it.h b/src/stm32lib/examples/DAC/OneChannel_NoiseWave/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/DAC/OneChannel_NoiseWave/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/main.c b/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/main.c new file mode 100755 index 0000000..9a45e6d --- /dev/null +++ b/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/main.c @@ -0,0 +1,232 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Init Structure definition */
+DAC_InitTypeDef DAC_InitStructure;
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+void Delay(vu32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* GPIO configuration */
+ GPIO_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* TIM2 Configuration */
+ TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
+ TIM_TimeBaseStructure.TIM_Period = 0xF;
+ TIM_TimeBaseStructure.TIM_Prescaler = 0xF;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0x0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
+
+ /* TIM2 TRGO selection */
+ TIM_SelectOutputTrigger(TIM2, TIM_TRGOSource_Update);
+
+ /* DAC channel1 Configuration */
+ DAC_InitStructure.DAC_Trigger = DAC_Trigger_T2_TRGO;
+ DAC_InitStructure.DAC_WaveGeneration = DAC_WaveGeneration_Triangle;
+ DAC_InitStructure.DAC_LFSRUnmask_TriangleAmplitude = DAC_TriangleAmplitude_2047;
+ DAC_InitStructure.DAC_OutputBuffer = DAC_OutputBuffer_Disable;
+ DAC_Init(DAC_Channel_1, &DAC_InitStructure);
+
+ /* DAC channel2 Configuration */
+ DAC_InitStructure.DAC_LFSRUnmask_TriangleAmplitude = DAC_TriangleAmplitude_1023;
+ DAC_Init(DAC_Channel_2, &DAC_InitStructure);
+
+ /* Enable DAC Channel1 */
+ DAC_Cmd(DAC_Channel_1, ENABLE);
+
+ /* Enable DAC Channel2 */
+ DAC_Cmd(DAC_Channel_2, ENABLE);
+
+ /* Set DAC dual channel DHR12RD register */
+ DAC_SetDualChannelData(DAC_Align_12b_R, 0x100, 0x100);
+
+ /* TIM2 enable counter */
+ TIM_Cmd(TIM2, ENABLE);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* AFIO and GPIOA Periph clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOA, ENABLE);
+ /* DAC Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_DAC, ENABLE);
+ /* TIM2 Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure DAC channe1 and DAC channel2 outputs pins */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 | GPIO_Pin_5;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for(; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/readme.txt b/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/readme.txt new file mode 100755 index 0000000..2deaeb0 --- /dev/null +++ b/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/readme.txt @@ -0,0 +1,69 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the DAC two channels triangle wave example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example describes how to use two DAC channels to generate two different
+signals with triangle waves on each DAC Channel output.
+
+DAC channels conversion are configured to be triggered by TIM2 TRGO with triangle
+wave generation. 12bit right data alignement is selected since we choose to acces
+both DAC_DHR12R1 and DAC_DHR12R2 registers.
+A triangle amplitude of 2047 is selected for DAC channel1 and 1023 for DAC channel2.
+Both DAC channels are then enabled. DAC Channel1 DHR12R1 and DAC channel2 DHR12R2
+registers are set to have a base output voltage of VREF/16 on each output.
+
+Once TIM2 is enabled, each TIM2 TRGO update event trigger both DAC channels start
+of conversion. The triangle counter is incremented, added to the base value and
+applied to the corresponding DAC channel output. The same calculation is repeated
+on each trigger.
+The triangle waves can be visualized by connecting both PA.04 and PA.05 pins to
+an oscilloscope.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board and can be
+easily tailored to any other hardware.
+
+ - Connect PA.04 and PA.05 pins to an oscilloscope
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_dac.c
+ + stm32f10x_tim.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/stm32f10x_conf.h b/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/stm32f10x_conf.h new file mode 100755 index 0000000..96884e4 --- /dev/null +++ b/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/stm32f10x_it.c b/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/stm32f10x_it.h b/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/DAC/TwoChannels_TriangleWave/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/ADC_TIM1/main.c b/src/stm32lib/examples/DMA/ADC_TIM1/main.c new file mode 100755 index 0000000..1a5b578 --- /dev/null +++ b/src/stm32lib/examples/DMA/ADC_TIM1/main.c @@ -0,0 +1,262 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define ADC1_DR_Address 0x4001244C
+#define TIM1_CCR1_Address 0x40012C34
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+ADC_InitTypeDef ADC_InitStructure;
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+DMA_InitTypeDef DMA_InitStructure;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+ /* DMA1 Channel5 configuration ----------------------------------------------*/
+ DMA_DeInit(DMA1_Channel5);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)TIM1_CCR1_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)ADC1_DR_Address;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
+ DMA_InitStructure.DMA_BufferSize = 1;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Disable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA1_Channel5, &DMA_InitStructure);
+ /* Enable DMA1 Channel5 */
+ DMA_Cmd(DMA1_Channel5, ENABLE);
+
+ /* ADC1 configuration ------------------------------------------------------*/
+ ADC_InitStructure.ADC_Mode = ADC_Mode_Independent;
+ ADC_InitStructure.ADC_ScanConvMode = DISABLE;
+ ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
+ ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
+ ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
+ ADC_InitStructure.ADC_NbrOfChannel = 1;
+ ADC_Init(ADC1, &ADC_InitStructure);
+
+ /* ADC1 RegularChannelConfig Test */
+ ADC_RegularChannelConfig(ADC1, ADC_Channel_14, 1, ADC_SampleTime_55Cycles5);
+
+ /* TIM1 configuration ------------------------------------------------------*/
+ /* Time Base configuration */
+ TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
+ TIM_TimeBaseStructure.TIM_Period = 0xFF0;
+ TIM_TimeBaseStructure.TIM_Prescaler = 0x0;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0x0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseInit(TIM1, &TIM_TimeBaseStructure);
+ /* Channel1 Configuration in PWM mode */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
+ TIM_OC1Init(TIM1, &TIM_OCInitStructure);
+
+ /* Enable TIM1 */
+ TIM_Cmd(TIM1, ENABLE);
+ /* Enable TIM1 outputs */
+ TIM_CtrlPWMOutputs(TIM1, ENABLE);
+
+ /* Enable TIM1 DMA interface */
+ TIM_DMACmd(TIM1, TIM_DMA_Update, ENABLE);
+
+ /* Enable ADC1 */
+ ADC_Cmd(ADC1, ENABLE);
+
+ /* Enable ADC1 reset calibaration register */
+ ADC_ResetCalibration(ADC1);
+ /* Check the end of ADC1 reset calibration register */
+ while(ADC_GetResetCalibrationStatus(ADC1));
+
+ /* Start ADC1 calibaration */
+ ADC_StartCalibration(ADC1);
+ /* Check the end of ADC1 calibration */
+ while(ADC_GetCalibrationStatus(ADC1));
+
+ /* Start ADC1 conversion */
+ ADC_SoftwareStartConvCmd(ADC1, ENABLE);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* ADCCLK = PCLK2/8 */
+ RCC_ADCCLKConfig(RCC_PCLK2_Div8);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* Enable DMA1 clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+ /* Enable GPIOA, GPIOC, ADC1 and TIM1 Periph clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOC |
+ RCC_APB2Periph_ADC1 | RCC_APB2Periph_TIM1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure TIM1 Channel1 output */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure ADC Channel14 as analog input */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 ;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/ADC_TIM1/readme.txt b/src/stm32lib/examples/DMA/ADC_TIM1/readme.txt new file mode 100755 index 0000000..dffb9f1 --- /dev/null +++ b/src/stm32lib/examples/DMA/ADC_TIM1/readme.txt @@ -0,0 +1,67 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the DMA ADC1 TIM1 example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to use a DMA channel to transfer
+continuously a data from a peripheral (ADC1) to another peripheral (TIM1) supporting
+DMA transfer.
+The ADC channel14 is configured to be converted continuously. TIM1_CH1 is configured
+to generate a PWM signal on its output.
+The dedicated DMA1 channel5 is configured to transfer in circular mode the last ADC
+channel14 converted value to the TIM1_CCR1 register. The DMA channel request is driven
+by the TIM1 update event. The duty cycle of TIM1_CH1 output signal is then changed
+each time the input voltage value on ADC channel14 pin is modified.
+The duty cycle variation can be visualized on oscilloscope on the TIM1_CH1 pin
+PA.08 while changing the analog input on ADC channel14 using the potentiometer.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+ - Connect a variable power supply 0-3.3V to ADC Channel14 mapped on pin PC.04
+ (potentiometer RV1 on STM3210B-EVAL or STM3210E-EVAL boards)
+ - Connect an oscilloscope to TIM1_CH1 (PA.08) pin
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_dma.c
+ + stm32f10x_rcc.c
+ + stm32f10x_gpio.c
+ + stm32f10x_adc.c
+ + stm32f10x_tim.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/DMA/ADC_TIM1/stm32f10x_conf.h b/src/stm32lib/examples/DMA/ADC_TIM1/stm32f10x_conf.h new file mode 100755 index 0000000..9b1c175 --- /dev/null +++ b/src/stm32lib/examples/DMA/ADC_TIM1/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+#define _ADC
+#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/ADC_TIM1/stm32f10x_it.c b/src/stm32lib/examples/DMA/ADC_TIM1/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/DMA/ADC_TIM1/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/ADC_TIM1/stm32f10x_it.h b/src/stm32lib/examples/DMA/ADC_TIM1/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/DMA/ADC_TIM1/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/FLASH_RAM/main.c b/src/stm32lib/examples/DMA/FLASH_RAM/main.c new file mode 100755 index 0000000..7fd0a60 --- /dev/null +++ b/src/stm32lib/examples/DMA/FLASH_RAM/main.c @@ -0,0 +1,241 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define BufferSize 32
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+DMA_InitTypeDef DMA_InitStructure;
+vu16 CurrDataCounterBegin = 0, CurrDataCounterEnd = 0;
+volatile TestStatus TransferStatus = FAILED;
+ErrorStatus HSEStartUpStatus;
+uc32 SRC_Const_Buffer[BufferSize]= {0x01020304,0x05060708,0x090A0B0C,0x0D0E0F10,
+ 0x11121314,0x15161718,0x191A1B1C,0x1D1E1F20,
+ 0x21222324,0x25262728,0x292A2B2C,0x2D2E2F30,
+ 0x31323334,0x35363738,0x393A3B3C,0x3D3E3F40,
+ 0x41424344,0x45464748,0x494A4B4C,0x4D4E4F50,
+ 0x51525354,0x55565758,0x595A5B5C,0x5D5E5F60,
+ 0x61626364,0x65666768,0x696A6B6C,0x6D6E6F70,
+ 0x71727374,0x75767778,0x797A7B7C,0x7D7E7F80};
+u32 DST_Buffer[BufferSize];
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(uc32* pBuffer, u32* pBuffer1, u16 BufferLength);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* DMA1 channel6 configuration */
+ DMA_DeInit(DMA1_Channel6);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)SRC_Const_Buffer;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)DST_Buffer;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = BufferSize;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Enable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Enable;
+ DMA_Init(DMA1_Channel6, &DMA_InitStructure);
+
+ /* Enable DMA1 Channel6 Transfer Complete interrupt */
+ DMA_ITConfig(DMA1_Channel6, DMA_IT_TC, ENABLE);
+
+ /* Get Current Data Counter value before transfer begins */
+ CurrDataCounterBegin = DMA_GetCurrDataCounter(DMA1_Channel6);
+
+ /* Enable DMA1 Channel6 transfer */
+ DMA_Cmd(DMA1_Channel6, ENABLE);
+
+ /* Wait the end of transmission */
+ while (CurrDataCounterEnd != 0)
+ {
+ }
+
+ /* Check if the transmitted and received data are equal */
+ TransferStatus = Buffercmp(SRC_Const_Buffer, DST_Buffer, BufferSize);
+ /* TransferStatus = PASSED, if the transmitted and received data
+ are the same */
+ /* TransferStatus = FAILED, if the transmitted and received data
+ are different */
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* Enable DMA1 clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Enable DMA1 channel6 IRQ Channel */
+ NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel6_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer, pBuffer1: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer identical to pBuffer1
+* FAILED: pBuffer differs from pBuffer1
+*******************************************************************************/
+TestStatus Buffercmp(uc32* pBuffer, u32* pBuffer1, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer != *pBuffer1)
+ {
+ return FAILED;
+ }
+
+ pBuffer++;
+ pBuffer1++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/FLASH_RAM/readme.txt b/src/stm32lib/examples/DMA/FLASH_RAM/readme.txt new file mode 100755 index 0000000..0810ef3 --- /dev/null +++ b/src/stm32lib/examples/DMA/FLASH_RAM/readme.txt @@ -0,0 +1,63 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the DMA FLASH to RAM example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to use a DMA channel to transfer
+a word data buffer from FLASH memory to embedded SRAM memory.
+
+DMA1 Channel6 is configured to transfer the contents of a 32-word data buffer
+stored in Flash memory to the reception buffer declared in RAM.
+
+The start of transfer is triggered by software. DMA1 Channel6 memory-to-memory
+transfer is enabled. Source and destination addresses incrementing is also enabled.
+The transfer is started by setting the Channel enable bit for DMA1 Channel6.
+At the end of the transfer a Transfer Complete interrupt is generated since it
+is enabled. Once interrupt is generated, the remaining data to be transferred is
+read which must be equal to 0. The Transfer Complete Interrupt pending bit is
+then cleared. A comparison between the source and destination buffers is done to
+check that all data have been correctly transferred.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_dma.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/DMA/FLASH_RAM/stm32f10x_conf.h b/src/stm32lib/examples/DMA/FLASH_RAM/stm32f10x_conf.h new file mode 100755 index 0000000..f44e0ae --- /dev/null +++ b/src/stm32lib/examples/DMA/FLASH_RAM/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+//#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+//#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/FLASH_RAM/stm32f10x_it.c b/src/stm32lib/examples/DMA/FLASH_RAM/stm32f10x_it.c new file mode 100755 index 0000000..9fb3587 --- /dev/null +++ b/src/stm32lib/examples/DMA/FLASH_RAM/stm32f10x_it.c @@ -0,0 +1,820 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+extern vu16 CurrDataCounterEnd;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+ /* Test on DMA1 Channel6 Transfer Complete interrupt */
+ if(DMA_GetITStatus(DMA1_IT_TC6))
+ {
+ /* Get Current Data Counter value after complete transfer */
+ CurrDataCounterEnd = DMA_GetCurrDataCounter(DMA1_Channel6);
+ /* Clear DMA1 Channel6 Half Transfer, Transfer Complete and Global interrupt pending bits */
+ DMA_ClearITPendingBit(DMA1_IT_GL6);
+ }
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/FLASH_RAM/stm32f10x_it.h b/src/stm32lib/examples/DMA/FLASH_RAM/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/DMA/FLASH_RAM/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/FSMC/fsmc_sram.c b/src/stm32lib/examples/DMA/FSMC/fsmc_sram.c new file mode 100755 index 0000000..ea7d248 --- /dev/null +++ b/src/stm32lib/examples/DMA/FSMC/fsmc_sram.c @@ -0,0 +1,161 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : fsmc_sram.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides a set of functions needed to drive the
+* IS61WV51216BLL SRAM memory mounted on STM3210E-EVAL board.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "fsmc_sram.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define Bank1_SRAM3_ADDR ((u32)0x68000000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : FSMC_SRAM_Init
+* Description : Configures the FSMC and GPIOs to interface with the SRAM memory.
+* This function must be called before any write/read operation
+* on the SRAM.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_SRAM_Init(void)
+{
+ FSMC_NORSRAMInitTypeDef FSMC_NORSRAMInitStructure;
+ FSMC_NORSRAMTimingInitTypeDef p;
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD | RCC_APB2Periph_GPIOG | RCC_APB2Periph_GPIOE |
+ RCC_APB2Periph_GPIOF, ENABLE);
+
+/*-- GPIO Configuration ------------------------------------------------------*/
+ /* SRAM Data lines configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_8 | GPIO_Pin_9 |
+ GPIO_Pin_10 | GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10 |
+ GPIO_Pin_11 | GPIO_Pin_12 | GPIO_Pin_13 | GPIO_Pin_14 |
+ GPIO_Pin_15;
+ GPIO_Init(GPIOE, &GPIO_InitStructure);
+
+ /* SRAM Address lines configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3 |
+ GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_12 | GPIO_Pin_13 |
+ GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_Init(GPIOF, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3 |
+ GPIO_Pin_4 | GPIO_Pin_5;
+ GPIO_Init(GPIOG, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12 | GPIO_Pin_13;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ /* NOE and NWE configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 |GPIO_Pin_5;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ /* NE3 configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_Init(GPIOG, &GPIO_InitStructure);
+
+ /* NBL0, NBL1 configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1;
+ GPIO_Init(GPIOE, &GPIO_InitStructure);
+
+/*-- FSMC Configuration ------------------------------------------------------*/
+ p.FSMC_AddressSetupTime = 0;
+ p.FSMC_AddressHoldTime = 0;
+ p.FSMC_DataSetupTime = 2;
+ p.FSMC_BusTurnAroundDuration = 0;
+ p.FSMC_CLKDivision = 0;
+ p.FSMC_DataLatency = 0;
+ p.FSMC_AccessMode = FSMC_AccessMode_A;
+
+ FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM3;
+ FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
+ FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+ FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+ FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_AsyncWait = FSMC_AsyncWait_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p;
+ FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p;
+
+ FSMC_NORSRAMInit(&FSMC_NORSRAMInitStructure);
+
+ /* Enable FSMC Bank1_SRAM Bank */
+ FSMC_NORSRAMCmd(FSMC_Bank1_NORSRAM3, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : FSMC_SRAM_WriteBuffer
+* Description : Writes a Half-word buffer to the FSMC SRAM memory.
+* Input : - pBuffer : pointer to buffer.
+* - WriteAddr : SRAM memory internal address from which the data
+* will be written.
+* - NumHalfwordToWrite : number of half-words to write.
+*
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_SRAM_WriteBuffer(u16* pBuffer, u32 WriteAddr, u32 NumHalfwordToWrite)
+{
+ for(; NumHalfwordToWrite != 0; NumHalfwordToWrite--) /* while there is data to write */
+ {
+ /* Transfer data to the memory */
+ *(u16 *) (Bank1_SRAM3_ADDR + WriteAddr) = *pBuffer++;
+
+ /* Increment the address*/
+ WriteAddr += 2;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_SRAM_ReadBuffer
+* Description : Reads a block of data from the FSMC SRAM memory.
+* Input : - pBuffer : pointer to the buffer that receives the data read
+* from the SRAM memory.
+* - ReadAddr : SRAM memory internal address to read from.
+* - NumHalfwordToRead : number of half-words to read.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_SRAM_ReadBuffer(u16* pBuffer, u32 ReadAddr, u32 NumHalfwordToRead)
+{
+ for(; NumHalfwordToRead != 0; NumHalfwordToRead--) /* while there is data to read */
+ {
+ /* Read a half-word from the memory */
+ *pBuffer++ = *(vu16*) (Bank1_SRAM3_ADDR + ReadAddr);
+
+ /* Increment the address*/
+ ReadAddr += 2;
+ }
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/FSMC/fsmc_sram.h b/src/stm32lib/examples/DMA/FSMC/fsmc_sram.h new file mode 100755 index 0000000..f599266 --- /dev/null +++ b/src/stm32lib/examples/DMA/FSMC/fsmc_sram.h @@ -0,0 +1,33 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : fsmc_sram.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Header for fsmc_sram.c file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __FSMC_SRAM_H
+#define __FSMC_SRAM_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void FSMC_SRAM_Init(void);
+void FSMC_SRAM_WriteBuffer(u16* pBuffer, u32 WriteAddr, u32 NumHalfwordToWrite);
+void FSMC_SRAM_ReadBuffer(u16* pBuffer, u32 ReadAddr, u32 NumHalfwordToRead);
+
+#endif /* __FSMC_SRAM_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/FSMC/main.c b/src/stm32lib/examples/DMA/FSMC/main.c new file mode 100755 index 0000000..f5b2df7 --- /dev/null +++ b/src/stm32lib/examples/DMA/FSMC/main.c @@ -0,0 +1,275 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "fsmc_sram.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define BufferSize 32
+#define Bank1_SRAM3_ADDR ((u32)0x68000000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+DMA_InitTypeDef DMA_InitStructure;
+ErrorStatus HSEStartUpStatus;
+volatile TestStatus TransferStatus;
+uc32 SRC_Const_Buffer[BufferSize]= {0x01020304,0x05060708,0x090A0B0C,0x0D0E0F10,
+ 0x11121314,0x15161718,0x191A1B1C,0x1D1E1F20,
+ 0x21222324,0x25262728,0x292A2B2C,0x2D2E2F30,
+ 0x31323334,0x35363738,0x393A3B3C,0x3D3E3F40,
+ 0x41424344,0x45464748,0x494A4B4C,0x4D4E4F50,
+ 0x51525354,0x55565758,0x595A5B5C,0x5D5E5F60,
+ 0x61626364,0x65666768,0x696A6B6C,0x6D6E6F70,
+ 0x71727374,0x75767778,0x797A7B7C,0x7D7E7F80};
+u8 DST_Buffer[4*BufferSize], Idx = 0;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+void Delay(vu32 nCount);
+TestStatus Buffercmp(uc32* pBuffer, u32* pBuffer1, u16 BufferLength);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* FSMC for SRAM and SRAM pins configuration */
+ FSMC_SRAM_Init();
+
+ /* Write to FSMC -----------------------------------------------------------*/
+ /* DMA2 channel5 configuration */
+ DMA_DeInit(DMA2_Channel5);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)SRC_Const_Buffer;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)Bank1_SRAM3_ADDR;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = 32;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Enable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Enable;
+ DMA_Init(DMA2_Channel5, &DMA_InitStructure);
+
+ /* Enable DMA2 channel5 */
+ DMA_Cmd(DMA2_Channel5, ENABLE);
+
+ /* Check if DMA2 channel5 transfer is finished */
+ while(!DMA_GetFlagStatus(DMA2_FLAG_TC5));
+
+ /* Clear DMA2 channel5 transfer complete flag bit */
+ DMA_ClearFlag(DMA2_FLAG_TC5);
+
+ /* Read from FSMC ----------------------------------------------------------*/
+ /* Destination buffer initialization */
+ for(Idx=0; Idx<128; Idx++) DST_Buffer[Idx]=0;
+
+ /* DMA1 channel3 configuration */
+ DMA_DeInit(DMA1_Channel3);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)Bank1_SRAM3_ADDR;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)DST_Buffer;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = 128;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Enable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Enable;
+ DMA_Init(DMA1_Channel3, &DMA_InitStructure);
+
+ /* Enable DMA1 channel3 */
+ DMA_Cmd(DMA1_Channel3, ENABLE);
+
+ /* Check if DMA1 channel3 transfer is finished */
+ while(!DMA_GetFlagStatus(DMA1_FLAG_TC3));
+
+ /* Clear DMA1 channel3 transfer complete flag bit */
+ DMA_ClearFlag(DMA1_FLAG_TC3);
+
+ /* Check if the transmitted and received data are equal */
+ TransferStatus = Buffercmp(SRC_Const_Buffer, (u32*)DST_Buffer, BufferSize);
+ /* TransferStatus = PASSED, if the transmitted and received data
+ are the same */
+ /* TransferStatus = FAILED, if the transmitted and received data
+ are different */
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* DMA1 and DMA2 clock enable */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1 | RCC_AHBPeriph_DMA2, ENABLE);
+ /* FSMC clock enable */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for(; nCount != 0; nCount--);
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer, pBuffer1: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer identical to pBuffer1
+* FAILED: pBuffer differs from pBuffer1
+*******************************************************************************/
+TestStatus Buffercmp(uc32* pBuffer, u32* pBuffer1, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer != *pBuffer1)
+ {
+ return FAILED;
+ }
+
+ pBuffer++;
+ pBuffer1++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/FSMC/readme.txt b/src/stm32lib/examples/DMA/FSMC/readme.txt new file mode 100755 index 0000000..854c17e --- /dev/null +++ b/src/stm32lib/examples/DMA/FSMC/readme.txt @@ -0,0 +1,70 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the DMA FSMC Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to use two DMA channels to transfer a
+word data buffer from Flash memory to external SRAM memory and to recuperate the written
+data from external SRAM to be stored in internal SRAM.
+DMA2 Channel5 is configured to transfer, word by word, the contents of a 32-word data
+buffer stored in Flash memory to the external SRAM memory interfaced by FSMC. The start
+of transfer is triggered by software. DMA2 Channel5 memory-to-memory transfer is enabled.
+Source and destination address incrementing is also enabled. The transfer is started by
+setting the Channel enable bit for DMA2 Channel5. A polling on the Transfer Complete flag
+is done to check the end of transfer. The DMA2 Channel5 Transfer complete flag is then cleared.
+DMA1 Channel3 is configured to transfer, byte by byte, the contents of the first 128Bytes
+of external SRAM to the internal SRAM memory. The start of transfer is triggered by software.
+DMA1 Channel3 memory-to-memory transfer is enabled. Source and destination address
+incrementing is also enabled. The transfer is started by setting the Channel enable bit for
+DMA1 Channel3. A polling on the Transfer Complete flag is done to check the end of transfer.
+the DMA1 Channel3 Transfer complete flag is then cleared.
+A comparison between the source and destination buffers is done to check that all data have been
+correctly transferred.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+fsmc_sram.c FSMC SRAM driver
+fsmc_sram.h Header for the fsmc_sram.c file
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board and can be
+easily tailored to any other hardware (with high density devices only).
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_dma.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_fsmc.c
+ + stm32f10x_gpio.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/DMA/FSMC/stm32f10x_conf.h b/src/stm32lib/examples/DMA/FSMC/stm32f10x_conf.h new file mode 100755 index 0000000..479290f --- /dev/null +++ b/src/stm32lib/examples/DMA/FSMC/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+#define _GPIOD
+#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/FSMC/stm32f10x_it.c b/src/stm32lib/examples/DMA/FSMC/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/DMA/FSMC/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/FSMC/stm32f10x_it.h b/src/stm32lib/examples/DMA/FSMC/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/DMA/FSMC/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/I2C_RAM/main.c b/src/stm32lib/examples/DMA/I2C_RAM/main.c new file mode 100755 index 0000000..5ef5d04 --- /dev/null +++ b/src/stm32lib/examples/DMA/I2C_RAM/main.c @@ -0,0 +1,305 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum { FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define I2C1_DR_Address 0x40005410
+#define I2C2_DR_Address 0x40005810
+#define I2C1_SLAVE_ADDRESS7 0x30
+#define I2C2_SLAVE_ADDRESS7 0x30
+#define BufferSize 8
+#define ClockSpeed 100000
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+I2C_InitTypeDef I2C_InitStructure;
+DMA_InitTypeDef DMA_InitStructure;
+u8 I2C1_Buffer_Tx[BufferSize] = {1, 2, 3, 4, 5, 6, 7, 8};
+u8 I2C2_Buffer_Rx[BufferSize];
+u8 Tx_Idx = 0, Rx_Idx = 0;
+volatile TestStatus TransferStatus;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer, u8* pBuffer1, u16 BufferLength);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+ /* DMA1 channel5 configuration ----------------------------------------------*/
+ DMA_DeInit(DMA1_Channel5);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)I2C2_DR_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)I2C2_Buffer_Rx;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = BufferSize;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_MemoryDataSize_Byte;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA1_Channel5, &DMA_InitStructure);
+
+ /* DMA1 channel6 configuration ----------------------------------------------*/
+ DMA_DeInit(DMA1_Channel6);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)I2C1_DR_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)I2C1_Buffer_Tx;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_Init(DMA1_Channel6, &DMA_InitStructure);
+
+ /* Enable I2C1 and I2C2 ----------------------------------------------------*/
+ I2C_Cmd(I2C1, ENABLE);
+ I2C_Cmd(I2C2, ENABLE);
+
+ /* I2C1 configuration ------------------------------------------------------*/
+ I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
+ I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2;
+ I2C_InitStructure.I2C_OwnAddress1 = I2C1_SLAVE_ADDRESS7;
+ I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
+ I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
+ I2C_InitStructure.I2C_ClockSpeed = ClockSpeed;
+ I2C_Init(I2C1, &I2C_InitStructure);
+ /* I2C2 configuration ------------------------------------------------------*/
+ I2C_InitStructure.I2C_OwnAddress1 = I2C2_SLAVE_ADDRESS7;
+ I2C_Init(I2C2, &I2C_InitStructure);
+
+ /*----- Transmission Phase -----*/
+ /* Send I2C1 START condition */
+ I2C_GenerateSTART(I2C1, ENABLE);
+ /* Test on I2C1 EV5 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_MODE_SELECT));
+ /* Send I2C2 slave Address for write */
+ I2C_Send7bitAddress(I2C1, I2C2_SLAVE_ADDRESS7, I2C_Direction_Transmitter);
+ /* Test on I2C2 EV1 and clear it */
+ while(!I2C_CheckEvent(I2C2, I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED));
+ /* Test on I2C1 EV6 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED));
+
+ /* Enable I2C2 DMA */
+ I2C_DMACmd(I2C2, ENABLE);
+ /* Enable I2C1 DMA */
+ I2C_DMACmd(I2C1, ENABLE);
+
+ /* Enable DMA1 Channel5 */
+ DMA_Cmd(DMA1_Channel5, ENABLE);
+ /* Enable DMA1 Channel6 */
+ DMA_Cmd(DMA1_Channel6, ENABLE);
+
+ /* DMA1 Channel5 transfer complete test */
+ while(!DMA_GetFlagStatus(DMA1_FLAG_TC5));
+ /* DMA1 Channel6 transfer complete test */
+ while(!DMA_GetFlagStatus(DMA1_FLAG_TC6));
+
+ /* Send I2C1 STOP Condition */
+ I2C_GenerateSTOP(I2C1, ENABLE);
+ /* Test on I2C2 EV4 */
+ while(!I2C_CheckEvent(I2C2, I2C_EVENT_SLAVE_STOP_DETECTED));
+ /* Clear I2C2 STOPF flag */
+ I2C_ClearFlag(I2C2, I2C_FLAG_STOPF);
+
+ /* Check if the transmitted and received data are equal */
+ TransferStatus = Buffercmp(I2C1_Buffer_Tx, I2C2_Buffer_Rx, BufferSize);
+ /* TransferStatus = PASSED, if the transmitted and received data
+ are the same */
+ /* TransferStatus = FAILED, if the transmitted and received data
+ are different */
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable DMA1 clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+ /* Enable GPIOB clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
+ /* Enable I2C1 and I2C2 clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1 | RCC_APB1Periph_I2C2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure I2C1 pins: SCL and SDA */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* Configure I2C2 pins: SCL and SDA */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer, pBuffer1: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer identical to pBuffer1
+* FAILED: pBuffer differs from pBuffer1
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer, u8* pBuffer1, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer != *pBuffer1)
+ {
+ return FAILED;
+ }
+
+ pBuffer++;
+ pBuffer1++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/I2C_RAM/readme.txt b/src/stm32lib/examples/DMA/I2C_RAM/readme.txt new file mode 100755 index 0000000..926e8c1 --- /dev/null +++ b/src/stm32lib/examples/DMA/I2C_RAM/readme.txt @@ -0,0 +1,67 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the DMA I2C example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to use two DMA channels to transfer a
+data buffer from memory to I2C2 through I2C1.
+I2C1 is set as the master transmitter and I2C2 as the slave receiver. DMA1 Channel5 is
+configured to store the data received from I2C2 into the Rx buffer (reception buffer).
+DMA1 Channel6 is configured to transfer data from the Tx buffer (transmission buffer) to
+the I2C1 DR register. After the generation of the Start condition and once the slave
+address has been acknowledged, DMA capability is enabled for both I2C1 and I2C2. As soon as the
+two I2C DMAEN bits are set in the I2C1_CR2 and I2C2_CR2 registers, the transmission of
+the Tx buffer is started by DMA1 Channel5 and at the same time the data received on
+I2C2 is stored in Rx buffer using DMA1 Channel6 . The transmitted and the received buffers
+are compared to check that all data have been correctly transferred.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+ - Connect I2C1 SCL pin (PB.06) to I2C2 SCL pin (PB.10)
+ - Connect I2C1 SDA pin (PB.07) to I2C2 SDA pin (PB.11)
+ - Check that a pull-up resistor is connected on one I2C SDA pin
+ - Check that a pull-up resistor is connected on one I2C SCL pin
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_dma.c
+ + stm32f10x_rcc.c
+ + stm32f10x_i2c.c
+ + stm32f10x_nvic.c
+ + stm32f10x_gpio.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/DMA/I2C_RAM/stm32f10x_conf.h b/src/stm32lib/examples/DMA/I2C_RAM/stm32f10x_conf.h new file mode 100755 index 0000000..6efe8da --- /dev/null +++ b/src/stm32lib/examples/DMA/I2C_RAM/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+#define _DMA1_Channel5
+#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+#define _I2C
+#define _I2C1
+#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/I2C_RAM/stm32f10x_it.c b/src/stm32lib/examples/DMA/I2C_RAM/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/DMA/I2C_RAM/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/I2C_RAM/stm32f10x_it.h b/src/stm32lib/examples/DMA/I2C_RAM/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/DMA/I2C_RAM/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/SPI_RAM/main.c b/src/stm32lib/examples/DMA/SPI_RAM/main.c new file mode 100755 index 0000000..5b07e60 --- /dev/null +++ b/src/stm32lib/examples/DMA/SPI_RAM/main.c @@ -0,0 +1,347 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum { FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define SPI1_DR_Address 0x4001300C
+#define SPI2_DR_Address 0x4000380C
+#define BufferSize 32
+#define CRCPolynomial 7
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+SPI_InitTypeDef SPI_InitStructure;
+DMA_InitTypeDef DMA_InitStructure;
+ErrorStatus HSEStartUpStatus;
+u8 SPI1_Buffer_Rx[BufferSize], SPI2_Buffer_Rx[BufferSize];
+u8 SPI1CRCValue = 0, SPI2CRCValue = 0;
+volatile TestStatus TransferStatus1 = FAILED, TransferStatus2 = FAILED;
+u8 SPI1_Buffer_Tx[BufferSize] = {0x01,0x02,0x03,0x04,0x05,0x06,0x07,0x08,0x09,
+ 0x0A,0x0B,0x0C,0x0D,0x0E,0x0F,0x10,0x11,0x12,
+ 0x13,0x14,0x15,0x16,0x17,0x18,0x19,0x1A,0x1B,
+ 0x1C,0x1D,0x1E,0x1F,0x20};
+u8 SPI2_Buffer_Tx[BufferSize] = {0x51,0x52,0x53,0x54,0x55,0x56,0x57,0x58,0x59,
+ 0x5A,0x5B,0x5C,0x5D,0x5E,0x5F,0x60,0x61,0x62,
+ 0x63,0x64,0x65,0x66,0x67,0x68,0x69,0x6A,0x6B,
+ 0x6C,0x6D,0x6E,0x6F,0x70};
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer, u8* pBuffer1, u16 BufferLength);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+ /* SPI1 configuration ------------------------------------------------------*/
+ SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
+ SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
+ SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
+ SPI_InitStructure.SPI_CPHA = SPI_CPHA_2Edge;
+ SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
+ SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
+ SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
+ SPI_InitStructure.SPI_CRCPolynomial = CRCPolynomial;
+ SPI_Init(SPI1, &SPI_InitStructure);
+
+ /* SPI2 configuration ------------------------------------------------------*/
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Slave;
+ SPI_Init(SPI2, &SPI_InitStructure);
+
+ /* DMA1 Channel2 configuration ----------------------------------------------*/
+ DMA_DeInit(DMA1_Channel2);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)SPI1_DR_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)SPI1_Buffer_Rx;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = BufferSize;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA1_Channel2, &DMA_InitStructure);
+
+ /* DMA1 Channel3 configuration ----------------------------------------------*/
+ DMA_DeInit(DMA1_Channel3);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)SPI1_DR_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)SPI1_Buffer_Tx;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_Low;
+ DMA_Init(DMA1_Channel3, &DMA_InitStructure);
+
+ /* DMA1 Channel4 configuration ----------------------------------------------*/
+ DMA_DeInit(DMA1_Channel4);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)SPI2_DR_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)SPI2_Buffer_Rx;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh;
+ DMA_Init(DMA1_Channel4, &DMA_InitStructure);
+
+ /* DMA1 Channel5 configuration ----------------------------------------------*/
+ DMA_DeInit(DMA1_Channel5);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)SPI2_DR_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)SPI2_Buffer_Tx;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
+ DMA_Init(DMA1_Channel5, &DMA_InitStructure);
+
+ /* Enable SPI1 DMA Tx request */
+ SPI_I2S_DMACmd(SPI1, SPI_I2S_DMAReq_Tx, ENABLE);
+ /* Enable SPI1 DMA Rx request */
+ SPI_I2S_DMACmd(SPI1, SPI_I2S_DMAReq_Rx, ENABLE);
+ /* Enable SPI2 DMA Tx request */
+ SPI_I2S_DMACmd(SPI2, SPI_I2S_DMAReq_Tx, ENABLE);
+ /* Enable SPI2 DMA Rx request */
+ SPI_I2S_DMACmd(SPI2, SPI_I2S_DMAReq_Rx, ENABLE);
+
+ /* Enable SPI1 CRC calculation */
+ SPI_CalculateCRC(SPI1, ENABLE);
+ /* Enable SPI2 CRC calculation */
+ SPI_CalculateCRC(SPI2, ENABLE);
+
+ /* Enable SPI2 */
+ SPI_Cmd(SPI2, ENABLE);
+ /* Enable SPI1 */
+ SPI_Cmd(SPI1, ENABLE);
+
+ /* Enable DMA1 channel5, channel4, channel3 and channel2 */
+ DMA_Cmd(DMA1_Channel2, ENABLE);
+ DMA_Cmd(DMA1_Channel4, ENABLE);
+ DMA_Cmd(DMA1_Channel5, ENABLE);
+ DMA_Cmd(DMA1_Channel3, ENABLE);
+
+ /* Transfer complete */
+ while(!DMA_GetFlagStatus(DMA1_FLAG_TC2));
+ while(!DMA_GetFlagStatus(DMA1_FLAG_TC4));
+ while(!DMA_GetFlagStatus(DMA1_FLAG_TC5));
+ while(!DMA_GetFlagStatus(DMA1_FLAG_TC3));
+
+ /* Wait for SPI1 data reception: CRC transmitted by SPI2 */
+ while(SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_RXNE)==RESET);
+ /* Wait for SPI2 data reception: CRC transmitted by SPI1 */
+ while(SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_RXNE)==RESET);
+
+ /* Check the corectness of written dada */
+ TransferStatus1 = Buffercmp(SPI2_Buffer_Rx, SPI1_Buffer_Tx, BufferSize);
+ TransferStatus2 = Buffercmp(SPI1_Buffer_Rx, SPI2_Buffer_Tx, BufferSize);
+ /* TransferStatus1, TransferStatus2 = PASSED, if the data transmitted and received
+ are correct */
+ /* TransferStatus1, TransferStatus2 = FAILED, if the data transmitted and received
+ are different */
+
+ /* Test on the SPI1 CRCR ERROR flag */
+ if ((SPI_I2S_GetFlagStatus(SPI1, SPI_FLAG_CRCERR)) != RESET)
+ {
+ TransferStatus1 = FAILED;
+ }
+ /* Test on the SPI2 CRCR ERROR flag */
+ if ((SPI_I2S_GetFlagStatus(SPI2, SPI_FLAG_CRCERR)) != RESET)
+ {
+ TransferStatus2 = FAILED;
+ }
+
+ /* Read SPI1 received CRC value */
+ SPI1CRCValue = SPI_I2S_ReceiveData(SPI1);
+ /* Read SPI2 received CRC value */
+ SPI2CRCValue = SPI_I2S_ReceiveData(SPI2);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK/2 */
+ RCC_PCLK2Config(RCC_HCLK_Div2);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* Enable DMA1 clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+ /* Enable GPIOA, GPIOB and SPI1 clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB |
+ RCC_APB2Periph_SPI1, ENABLE);
+ /* Enable SPI2 Periph clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure SPI1 pins: SCK, MISO and MOSI */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5 | GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure SPI2 pins: SCK, MISO and MOSI */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer, pBuffer1: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer identical to pBuffer1
+* FAILED: pBuffer differs from pBuffer1
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer, u8* pBuffer1, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer != *pBuffer1)
+ {
+ return FAILED;
+ }
+
+ pBuffer++;
+ pBuffer1++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/SPI_RAM/readme.txt b/src/stm32lib/examples/DMA/SPI_RAM/readme.txt new file mode 100755 index 0000000..93a6478 --- /dev/null +++ b/src/stm32lib/examples/DMA/SPI_RAM/readme.txt @@ -0,0 +1,80 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the DMA SPI example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to use four DMA channels to transfer a
+data buffer from memory to SPI2 through SPI1 and a second data buffer from memory
+to SPI1 through SPI2 in ful-duplex mode.
+
+The NSS pins are configured by software to set SPI1 as master and SPI2 as slave.
+DMA1 Channel2 and Channel4 are configured to store, respectively, the data
+received by SPI1 into the SPI1_Buffer_Rx and the data received by SPI2 into the
+SPI2_Buffer_Rx.
+DMA1 Channel3 is configured to transfer data from the SPI1_Buffer_Tx to the
+SPI1_DR register for transmission to SPI2. DMA1 Channel5 is configured to transfer
+data from the SPI2_Buffer_Tx to the SPI2_DR register for transmission to SPI1.
+
+As soon as the two SPIs TxDMAEN and RxDMAEN bits are set in the SPI1_CR2 and
+SPI2_CR2 registers, DMA1 Channel3 and Channel5 start transmitting, respectively,
+the SPI1 and SPI2 Tx buffers at the same time. At the same moment, the data received
+on SPI1 and SPI2 are stored by DMA1 Channel2 and Channel4 to the SPI1 and SPI2
+Rx buffers, respectively.
+
+A polling on all Transfer complete flags are done for all used DMA channels to
+check the end of all DMA channels transfers. The last received data on SPI1 and
+SPI2 are the CRC values sent by each SPI to the other. The transmitted and received
+buffers are compared to check that all data have been correctly transferred.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+ - Connect SPI1 SCK pin (PA.05) to SPI2 SCK pin (PB.13)
+ - Connect SPI1 MISO pin (PA.06) to SPI2 MISO pin (PB.14)
+ - Connect SPI1 MOSI pin (PA.07) to SPI2 MOSI pin (PB.15)
+
+Note: in STM3210E-EVAL board, the jumper 14 (USB Disconnect) must be set in
+ position 1<->2 in order to not interfer with SPI2 MISO pin PB14.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_dma.c
+ + stm32f10x_rcc.c
+ + stm32f10x_spi.c
+ + stm32f10x_nvic.c
+ + stm32f10x_gpio.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/DMA/SPI_RAM/stm32f10x_conf.h b/src/stm32lib/examples/DMA/SPI_RAM/stm32f10x_conf.h new file mode 100755 index 0000000..30d20df --- /dev/null +++ b/src/stm32lib/examples/DMA/SPI_RAM/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+//#define _DMA1_Channel1
+#define _DMA1_Channel2
+#define _DMA1_Channel3
+#define _DMA1_Channel4
+#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+#define _SPI
+#define _SPI1
+#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/SPI_RAM/stm32f10x_it.c b/src/stm32lib/examples/DMA/SPI_RAM/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/DMA/SPI_RAM/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/DMA/SPI_RAM/stm32f10x_it.h b/src/stm32lib/examples/DMA/SPI_RAM/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/DMA/SPI_RAM/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/EXTI/main.c b/src/stm32lib/examples/EXTI/main.c new file mode 100755 index 0000000..80d0741 --- /dev/null +++ b/src/stm32lib/examples/EXTI/main.c @@ -0,0 +1,208 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+EXTI_InitTypeDef EXTI_InitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+ /* Connect Key Button EXTI Line to Key Button GPIO Pin */
+ GPIO_EXTILineConfig(GPIO_PORT_SOURCE_KEY_BUTTON, GPIO_PIN_SOURCE_KEY_BUTTON);
+
+ /* Configure Key Button EXTI Line to generate an interrupt on falling edge */
+ EXTI_InitStructure.EXTI_Line = EXTI_LINE_KEY_BUTTON;
+ EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
+ EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+ EXTI_Init(&EXTI_InitStructure);
+
+ /* Generate software interrupt: simulate a falling edge applied on Key Button EXTI line */
+ EXTI_GenerateSWInterrupt(EXTI_LINE_KEY_BUTTON);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable Key Button GPIO Port, GPIO_LED and AFIO clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_KEY_BUTTON | RCC_APB2Periph_GPIO_LED
+ | RCC_APB2Periph_AFIO, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure GPIO Led pin 6 as Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ /* Configure Key Button GPIO Pin as input floating (Key Button EXTI Line) */
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_KEY_BUTTON;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIO_KEY_BUTTON, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Configure one bit for preemption priority */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
+
+ /* Enable the EXTI9_5 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = EXTI9_5_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/EXTI/platform_config.h b/src/stm32lib/examples/EXTI/platform_config.h new file mode 100755 index 0000000..3deb7ba --- /dev/null +++ b/src/stm32lib/examples/EXTI/platform_config.h @@ -0,0 +1,56 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+ #define GPIO_KEY_BUTTON GPIOB
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOB
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_9
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line9
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOB
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource9
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+ #define GPIO_KEY_BUTTON GPIOG
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOG
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_8
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line8
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOG
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource8
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/EXTI/readme.txt b/src/stm32lib/examples/EXTI/readme.txt new file mode 100755 index 0000000..f940e11 --- /dev/null +++ b/src/stm32lib/examples/EXTI/readme.txt @@ -0,0 +1,67 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the EXTI Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to configure an external interrupt line.
+In this example, an EXTI line is configured to generate an interrupt on each
+falling edge. In the interrupt routine a led connected to a specific GPIO pin is
+toggled.
+This led will be toggled due to the softawre interrupt generated on the EXTI Line
+then at each falling edge.
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1 led connected to PC.06 pin
+ - Use the Key push-button connected to pin PB.09 (EXTI Line9).
+
+ + STM3210E-EVAL
+ - Use LD1 led connected to PF.06 pin
+ - Use the Key push-button connected to pin PG.08 (EXTI Line8).
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_exti.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/EXTI/stm32f10x_conf.h b/src/stm32lib/examples/EXTI/stm32f10x_conf.h new file mode 100755 index 0000000..bf5ef58 --- /dev/null +++ b/src/stm32lib/examples/EXTI/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/EXTI/stm32f10x_it.c b/src/stm32lib/examples/EXTI/stm32f10x_it.c new file mode 100755 index 0000000..1138095 --- /dev/null +++ b/src/stm32lib/examples/EXTI/stm32f10x_it.c @@ -0,0 +1,819 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+ if(EXTI_GetITStatus(EXTI_LINE_KEY_BUTTON) != RESET)
+ {
+ /* Toggle GPIO_LED pin 6 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_6, (BitAction)((1-GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_6))));
+
+ /* Clear the Key Button EXTI line pending bit */
+ EXTI_ClearITPendingBit(EXTI_LINE_KEY_BUTTON);
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/EXTI/stm32f10x_it.h b/src/stm32lib/examples/EXTI/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/EXTI/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FLASH/Program/main.c b/src/stm32lib/examples/FLASH/Program/main.c new file mode 100755 index 0000000..38dcb62 --- /dev/null +++ b/src/stm32lib/examples/FLASH/Program/main.c @@ -0,0 +1,201 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define StartAddr ((u32)0x08008000)
+#define EndAddr ((u32)0x0800C000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+u32 EraseCounter = 0x00, Address = 0x00;
+u32 Data;
+vu32 NbrOfPage = 0x00;
+volatile FLASH_Status FLASHStatus;
+volatile TestStatus MemoryProgramStatus;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void NVIC_Configuration(void);
+void RCC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ FLASHStatus = FLASH_COMPLETE;
+ MemoryProgramStatus = PASSED;
+ Data = 0x15041979;
+
+ /* RCC Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* Unlock the Flash Program Erase controller */
+ FLASH_Unlock();
+
+ /* Define the number of page to be erased */
+ NbrOfPage = (EndAddr - StartAddr) / FLASH_PAGE_SIZE;
+
+ /* Clear All pending flags */
+ FLASH_ClearFlag(FLASH_FLAG_BSY | FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
+
+ /* Erase the FLASH pages */
+ for(EraseCounter = 0; (EraseCounter < NbrOfPage) && (FLASHStatus == FLASH_COMPLETE); EraseCounter++)
+ {
+ FLASHStatus = FLASH_ErasePage(StartAddr + (FLASH_PAGE_SIZE * EraseCounter));
+ }
+
+ /* FLASH Word program of data 0x15041979 at addresses defined by StartAddr and EndAddr*/
+ Address = StartAddr;
+
+ while((Address < EndAddr) && (FLASHStatus == FLASH_COMPLETE))
+ {
+ FLASHStatus = FLASH_ProgramWord(Address, Data);
+ Address = Address + 4;
+ }
+
+ /* Check the corectness of written data */
+ Address = StartAddr;
+
+ while((Address < EndAddr) && (MemoryProgramStatus != FAILED))
+ {
+ if((*(vu32*) Address) != Data)
+ {
+ MemoryProgramStatus = FAILED;
+ }
+ Address += 4;
+ }
+
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FLASH/Program/platform_config.h b/src/stm32lib/examples/FLASH/Program/platform_config.h new file mode 100755 index 0000000..c7ab708 --- /dev/null +++ b/src/stm32lib/examples/FLASH/Program/platform_config.h @@ -0,0 +1,42 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define FLASH_PAGE_SIZE ((u16)0x400)
+#elif defined USE_STM3210E_EVAL
+ #define FLASH_PAGE_SIZE ((u16)0x800)
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FLASH/Program/readme.txt b/src/stm32lib/examples/FLASH/Program/readme.txt new file mode 100755 index 0000000..a26a157 --- /dev/null +++ b/src/stm32lib/examples/FLASH/Program/readme.txt @@ -0,0 +1,64 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the FLASH Program Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to program the STM32F10x FLASH.
+
+After Reset, the Flash memory Program/Erase Controller is locked. To unlock it,
+the FLASH_Unlock function is used.
+Before programming the desired addresses, an erase operation is performed using
+the flash erase page feature. The erase procedure starts with the calculation of
+the number of pages to be used. Then all these pages will be erased one by one by
+calling FLASH_ErasePage function.
+
+Once this operation is finished, the programming operation will be performed by
+using the FLASH_ProgramWord function. The written data is then checked and the
+result of the programming operation is stored into the MemoryProgramStatus variable.
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+Note: "#define _FLASH_PROG" should be uncommented in the stm32f10x_conf.h file
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32F10x_lib.c
+ + stm32F10x_flash.c
+ + stm32F10x_rcc.c
+ + stm32F10x_nvic.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/FLASH/Program/stm32f10x_conf.h b/src/stm32lib/examples/FLASH/Program/stm32f10x_conf.h new file mode 100755 index 0000000..2efbca8 --- /dev/null +++ b/src/stm32lib/examples/FLASH/Program/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+#define _FLASH_PROG
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+//#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+//#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FLASH/Program/stm32f10x_it.c b/src/stm32lib/examples/FLASH/Program/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/FLASH/Program/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FLASH/Program/stm32f10x_it.h b/src/stm32lib/examples/FLASH/Program/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/FLASH/Program/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FLASH/Write_Protection/main.c b/src/stm32lib/examples/FLASH/Write_Protection/main.c new file mode 100755 index 0000000..ccae71f --- /dev/null +++ b/src/stm32lib/examples/FLASH/Write_Protection/main.c @@ -0,0 +1,247 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define StartAddr ((u32)0x08006000)
+#define EndAddr ((u32)0x08008000)
+
+/* Uncomment this line to Enable Write Protection */
+//#define WriteProtection_Enable
+/* Uncomment this line to Disable Write Protection */
+#define WriteProtection_Disable
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+u32 EraseCounter, Address;
+u16 Data;
+vu32 WRPR_Value = 0xFFFFFFFF, ProtectedPages = 0x0;
+vu8 NbrOfPage;
+volatile FLASH_Status FLASHStatus;
+volatile TestStatus MemoryProgramStatus;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void NVIC_Configuration(void);
+void RCC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ FLASHStatus = FLASH_COMPLETE;
+ MemoryProgramStatus = PASSED;
+ Data = 0x1753;
+ EraseCounter = 0x0;
+
+ /* RCC Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* Unlock the Flash Program Erase controller */
+ FLASH_Unlock();
+
+ /* Define the number of page to be erased */
+ NbrOfPage = (EndAddr - StartAddr) / FLASH_PAGE_SIZE;
+
+ FLASH_ClearFlag(FLASH_FLAG_BSY | FLASH_FLAG_EOP|FLASH_FLAG_PGERR |FLASH_FLAG_WRPRTERR);
+
+ /* Get pages write protection status */
+ WRPR_Value = FLASH_GetWriteProtectionOptionByte();
+ ProtectedPages = WRPR_Value & 0x000000C0;
+
+#ifdef WriteProtection_Disable
+ if (ProtectedPages == 0x00)
+ {/* Pages are write protected */
+
+ /* Disable the write protection */
+ FLASHStatus = FLASH_EraseOptionBytes();
+
+ /* Generate System Reset to load the new option byte values */
+ NVIC_GenerateSystemReset();
+ }
+#else
+ #ifdef WriteProtection_Enable
+
+ if (ProtectedPages != 0x00)
+ {/* Pages not write protected */
+ #ifdef USE_STM3210B_EVAL
+ /* Enable the pages write protection */
+ FLASHStatus = FLASH_EnableWriteProtection(FLASH_WRProt_Pages24to27 |FLASH_WRProt_Pages28to31);
+ #else
+ /* Enable the pages write protection */
+ FLASHStatus = FLASH_EnableWriteProtection(FLASH_WRProt_Pages12to13 |FLASH_WRProt_Pages14to15);
+ #endif
+ /* Generate System Reset to load the new option byte values */
+ NVIC_GenerateSystemReset();
+ }
+ #endif
+#endif
+
+ /* If Pages are not write protected, perform erase and program operations
+ Else nothing */
+ if (ProtectedPages != 0x00)
+ {
+ /* Clear All pending flags */
+ FLASH_ClearFlag(FLASH_FLAG_BSY | FLASH_FLAG_EOP|FLASH_FLAG_PGERR |FLASH_FLAG_WRPRTERR);
+
+ /* erase the FLASH pages */
+ for(EraseCounter = 0; (EraseCounter < NbrOfPage) && (FLASHStatus == FLASH_COMPLETE); EraseCounter++)
+ {
+ FLASHStatus = FLASH_ErasePage(StartAddr + (FLASH_PAGE_SIZE * EraseCounter));
+ }
+
+ /* FLASH Half Word program of data 0x1753 at addresses defined by StartAddr and EndAddr */
+ Address = StartAddr;
+
+ while((Address < EndAddr) && (FLASHStatus == FLASH_COMPLETE))
+ {
+ FLASHStatus = FLASH_ProgramHalfWord(Address, Data);
+ Address = Address + 2;
+ }
+
+ /* Check the corectness of written data */
+ Address = StartAddr;
+
+ while((Address < EndAddr) && (MemoryProgramStatus != FAILED))
+ {
+ if((*(vu16*) Address) != Data)
+ {
+ MemoryProgramStatus = FAILED;
+ }
+ Address += 2;
+ }
+
+ }
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FLASH/Write_Protection/platform_config.h b/src/stm32lib/examples/FLASH/Write_Protection/platform_config.h new file mode 100755 index 0000000..c7ab708 --- /dev/null +++ b/src/stm32lib/examples/FLASH/Write_Protection/platform_config.h @@ -0,0 +1,42 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define FLASH_PAGE_SIZE ((u16)0x400)
+#elif defined USE_STM3210E_EVAL
+ #define FLASH_PAGE_SIZE ((u16)0x800)
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FLASH/Write_Protection/readme.txt b/src/stm32lib/examples/FLASH/Write_Protection/readme.txt new file mode 100755 index 0000000..ffc3b3f --- /dev/null +++ b/src/stm32lib/examples/FLASH/Write_Protection/readme.txt @@ -0,0 +1,76 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the FLASH Write_Protection Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to enable and disable the write protection
+for the STM32F10x FLASH:
+
+- Enable Write protection:
+ To enable the Write Protection, uncomment the line "#define WriteProtection_Enable"
+ in main.c file.
+
+ To protect a set of pages, the user has to call the function FLASH_EnableWriteProtection.
+ The parameter of this function will define the number of pages to be protected.
+ To load the new option byte values, a system Reset is necessary, for this, the
+ function NVIC_GenerateSystemReset() is used.
+
+- Disable Write protection:
+ To disable the Write Protection, uncomment the line "#define WriteProtection_Disable"
+ in main.c file.
+
+ To disable the write protection of the STM32F10x Flash, an erase of the Option
+ Bytes is necessary. This operation is done by the function FLASH_EraseOptionBytes.
+ To load the new option byte values, a system Reset is necessary, for this, the
+ function NVIC_GenerateSystemReset() is used.
+
+If the desired pages are not write protected, an erase and a write operation are
+performed.
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+Note: "#define _FLASH_PROG" should be uncommented in the stm32f10x_conf.h file
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32F10x_lib.c
+ + stm32F10x_flash.c
+ + stm32F10x_rcc.c
+ + stm32F10x_nvic.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/FLASH/Write_Protection/stm32f10x_conf.h b/src/stm32lib/examples/FLASH/Write_Protection/stm32f10x_conf.h new file mode 100755 index 0000000..2efbca8 --- /dev/null +++ b/src/stm32lib/examples/FLASH/Write_Protection/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+#define _FLASH_PROG
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+//#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+//#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FLASH/Write_Protection/stm32f10x_it.c b/src/stm32lib/examples/FLASH/Write_Protection/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/FLASH/Write_Protection/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FLASH/Write_Protection/stm32f10x_it.h b/src/stm32lib/examples/FLASH/Write_Protection/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/FLASH/Write_Protection/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NAND/fsmc_nand.c b/src/stm32lib/examples/FSMC/NAND/fsmc_nand.c new file mode 100755 index 0000000..7cc15e7 --- /dev/null +++ b/src/stm32lib/examples/FSMC/NAND/fsmc_nand.c @@ -0,0 +1,491 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : fsmc_nand.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides a set of functions needed to drive the
+* NAND512W3A2 memory mounted on STM3210E-EVAL board.
+********************************************************************************
+* 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.
+*******************************************************************************/
+/* Includes ------------------------------------------------------------------*/
+#include "fsmc_nand.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+#define FSMC_Bank_NAND FSMC_Bank2_NAND
+#define Bank_NAND_ADDR Bank2_NAND_ADDR
+#define Bank2_NAND_ADDR ((u32)0x70000000)
+
+/* Private macro -------------------------------------------------------------*/
+#define ROW_ADDRESS (Address.Page + (Address.Block + (Address.Zone * NAND_ZONE_SIZE)) * NAND_BLOCK_SIZE)
+
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : FSMC_NAND_Init
+* Description : Configures the FSMC and GPIOs to interface with the NAND memory.
+* This function must be called before any write/read operation
+* on the NAND.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NAND_Init(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+ FSMC_NANDInitTypeDef FSMC_NANDInitStructure;
+ FSMC_NAND_PCCARDTimingInitTypeDef p;
+
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD | RCC_APB2Periph_GPIOE |
+ RCC_APB2Periph_GPIOF | RCC_APB2Periph_GPIOG, ENABLE);
+
+/*-- GPIO Configuration ------------------------------------------------------*/
+/* CLE, ALE, D0->D3, NOE, NWE and NCE2 NAND pin configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12 | GPIO_Pin_14 | GPIO_Pin_15 |
+ GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_4 | GPIO_Pin_5 |
+ GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+/* D4->D7 NAND pin configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10;
+
+ GPIO_Init(GPIOE, &GPIO_InitStructure);
+
+
+/* NWAIT NAND pin configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
+
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+/* INT2 NAND pin configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
+ GPIO_Init(GPIOG, &GPIO_InitStructure);
+
+ /*-- FSMC Configuration ------------------------------------------------------*/
+ p.FSMC_SetupTime = 0x1;
+ p.FSMC_WaitSetupTime = 0x3;
+ p.FSMC_HoldSetupTime = 0x2;
+ p.FSMC_HiZSetupTime = 0x1;
+
+ FSMC_NANDInitStructure.FSMC_Bank = FSMC_Bank2_NAND;
+ FSMC_NANDInitStructure.FSMC_Waitfeature = FSMC_Waitfeature_Enable;
+ FSMC_NANDInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b;
+ FSMC_NANDInitStructure.FSMC_ECC = FSMC_ECC_Enable;
+ FSMC_NANDInitStructure.FSMC_ECCPageSize = FSMC_ECCPageSize_512Bytes;
+ FSMC_NANDInitStructure.FSMC_AddressLowMapping = FSMC_AddressLowMapping_Direct;
+ FSMC_NANDInitStructure.FSMC_TCLRSetupTime = 0x00;
+ FSMC_NANDInitStructure.FSMC_TARSetupTime = 0x00;
+ FSMC_NANDInitStructure.FSMC_CommonSpaceTimingStruct = &p;
+ FSMC_NANDInitStructure.FSMC_AttributeSpaceTimingStruct = &p;
+
+ FSMC_NANDInit(&FSMC_NANDInitStructure);
+
+ /* FSMC NAND Bank Cmd Test */
+ FSMC_NANDCmd(FSMC_Bank2_NAND, ENABLE);
+}
+
+/******************************************************************************
+* Function Name : FSMC_NAND_ReadID
+* Description : Reads NAND memory's ID.
+* Input : - NAND_ID: pointer to a NAND_IDTypeDef structure which will hold
+* the Manufacturer and Device ID.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NAND_ReadID(NAND_IDTypeDef* NAND_ID)
+{
+ u32 data = 0;
+
+ /* Send Command to the command area */
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = 0x90;
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = 0x00;
+
+ /* Sequence to read ID from NAND flash */
+ data = *(vu32 *)(Bank_NAND_ADDR | DATA_AREA);
+
+ NAND_ID->Maker_ID = ADDR_1st_CYCLE (data);
+ NAND_ID->Device_ID = ADDR_2nd_CYCLE (data);
+ NAND_ID->Third_ID = ADDR_3rd_CYCLE (data);
+ NAND_ID->Fourth_ID = ADDR_4th_CYCLE (data);
+}
+
+/******************************************************************************
+* Function Name : FSMC_NAND_WriteSmallPage
+* Description : This routine is for writing one or several 512 Bytes Page size.
+* Input : - pBuffer: pointer on the Buffer containing data to be written
+* - Address: First page address
+* - NumPageToWrite: Number of page to write
+* Output : None
+* Return : New status of the NAND operation. This parameter can be:
+* - NAND_TIMEOUT_ERROR: when the previous operation generate
+* a Timeout error
+* - NAND_READY: when memory is ready for the next operation
+* And the new status of the increment address operation. It can be:
+* - NAND_VALID_ADDRESS: When the new address is valid address
+* - NAND_INVALID_ADDRESS: When the new address is invalid address
+*******************************************************************************/
+u32 FSMC_NAND_WriteSmallPage(u8 *pBuffer, NAND_ADDRESS Address, u32 NumPageToWrite)
+{
+ u32 index = 0x00, numpagewritten = 0x00, addressstatus = NAND_VALID_ADDRESS;
+ u32 status = NAND_READY, size = 0x00;
+
+ while((NumPageToWrite != 0x00) && (addressstatus == NAND_VALID_ADDRESS) && (status == NAND_READY))
+ {
+ /* Page write command and address */
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = NAND_CMD_AREA_A;
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = NAND_CMD_WRITE0;
+
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = 0x00;
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_1st_CYCLE(ROW_ADDRESS);
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_2nd_CYCLE(ROW_ADDRESS);
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_3rd_CYCLE(ROW_ADDRESS);
+
+ /* Calculate the size */
+ size = NAND_PAGE_SIZE + (NAND_PAGE_SIZE * numpagewritten);
+
+ /* Write data */
+ for(; index < size; index++)
+ {
+ *(vu8 *)(Bank_NAND_ADDR | DATA_AREA) = pBuffer[index];
+ }
+
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = NAND_CMD_WRITE_TRUE1;
+
+ /* Check status for successful operation */
+ status = FSMC_NAND_GetStatus();
+
+ if(status == NAND_READY)
+ {
+ numpagewritten++;
+
+ NumPageToWrite--;
+
+ /* Calculate Next small page Address */
+ addressstatus = FSMC_NAND_AddressIncrement(&Address);
+ }
+ }
+
+ return (status | addressstatus);
+}
+
+/******************************************************************************
+* Function Name : FSMC_NAND_ReadSmallPage
+* Description : This routine is for sequential read from one or several
+* 512 Bytes Page size.
+* Input : - pBuffer: pointer on the Buffer to fill
+* - Address: First page address
+* - NumPageToRead: Number of page to read
+* Output : None
+* Return : New status of the NAND operation. This parameter can be:
+* - NAND_TIMEOUT_ERROR: when the previous operation generate
+* a Timeout error
+* - NAND_READY: when memory is ready for the next operation
+* And the new status of the increment address operation. It can be:
+* - NAND_VALID_ADDRESS: When the new address is valid address
+* - NAND_INVALID_ADDRESS: When the new address is invalid address
+*******************************************************************************/
+u32 FSMC_NAND_ReadSmallPage(u8 *pBuffer, NAND_ADDRESS Address, u32 NumPageToRead)
+{
+ u32 index = 0x00, numpageread = 0x00, addressstatus = NAND_VALID_ADDRESS;
+ u32 status = NAND_READY, size = 0x00;
+
+ while((NumPageToRead != 0x0) && (addressstatus == NAND_VALID_ADDRESS))
+ {
+ /* Page Read command and page address */
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = NAND_CMD_AREA_A;
+
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = 0x00;
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_1st_CYCLE(ROW_ADDRESS);
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_2nd_CYCLE(ROW_ADDRESS);
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_3rd_CYCLE(ROW_ADDRESS);
+
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = NAND_CMD_AREA_TRUE1;
+
+ /* Calculate the size */
+ size = NAND_PAGE_SIZE + (NAND_PAGE_SIZE * numpageread);
+
+ /* Get Data into Buffer */
+ for(; index < size; index++)
+ {
+ pBuffer[index]= *(vu8 *)(Bank_NAND_ADDR | DATA_AREA);
+ }
+
+ numpageread++;
+
+ NumPageToRead--;
+
+ /* Calculate page address */
+ addressstatus = FSMC_NAND_AddressIncrement(&Address);
+ }
+
+ status = FSMC_NAND_GetStatus();
+
+ return (status | addressstatus);
+}
+
+/******************************************************************************
+* Function Name : FSMC_NAND_WriteSpareArea
+* Description : This routine write the spare area information for the specified
+* pages addresses.
+* Input : - pBuffer: pointer on the Buffer containing data to be written
+* - Address: First page address
+* - NumSpareAreaTowrite: Number of Spare Area to write
+* Output : None
+* Return : New status of the NAND operation. This parameter can be:
+* - NAND_TIMEOUT_ERROR: when the previous operation generate
+* a Timeout error
+* - NAND_READY: when memory is ready for the next operation
+* And the new status of the increment address operation. It can be:
+* - NAND_VALID_ADDRESS: When the new address is valid address
+* - NAND_INVALID_ADDRESS: When the new address is invalid address
+*******************************************************************************/
+u32 FSMC_NAND_WriteSpareArea(u8 *pBuffer, NAND_ADDRESS Address, u32 NumSpareAreaTowrite)
+{
+ u32 index = 0x00, numsparesreawritten = 0x00, addressstatus = NAND_VALID_ADDRESS;
+ u32 status = NAND_READY, size = 0x00;
+
+ while((NumSpareAreaTowrite != 0x00) && (addressstatus == NAND_VALID_ADDRESS) && (status == NAND_READY))
+ {
+ /* Page write Spare area command and address */
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = NAND_CMD_AREA_C;
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = NAND_CMD_WRITE0;
+
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = 0x00;
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_1st_CYCLE(ROW_ADDRESS);
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_2nd_CYCLE(ROW_ADDRESS);
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_3rd_CYCLE(ROW_ADDRESS);
+
+ /* Calculate the size */
+ size = NAND_SPARE_AREA_SIZE + (NAND_SPARE_AREA_SIZE * numsparesreawritten);
+
+ /* Write the data */
+ for(; index < size; index++)
+ {
+ *(vu8 *)(Bank_NAND_ADDR | DATA_AREA) = pBuffer[index];
+ }
+
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = NAND_CMD_WRITE_TRUE1;
+
+ /* Check status for successful operation */
+ status = FSMC_NAND_GetStatus();
+
+ if(status == NAND_READY)
+ {
+ numsparesreawritten++;
+
+ NumSpareAreaTowrite--;
+
+ /* Calculate Next page Address */
+ addressstatus = FSMC_NAND_AddressIncrement(&Address);
+ }
+ }
+
+ return (status | addressstatus);
+}
+
+/******************************************************************************
+* Function Name : FSMC_NAND_ReadSpareArea
+* Description : This routine read the spare area information from the specified
+* pages addresses.
+* Input : - pBuffer: pointer on the Buffer to fill
+* - Address: First page address
+* - NumSpareAreaToRead: Number of Spare Area to read
+* Output : None
+* Return : New status of the NAND operation. This parameter can be:
+* - NAND_TIMEOUT_ERROR: when the previous operation generate
+* a Timeout error
+* - NAND_READY: when memory is ready for the next operation
+* And the new status of the increment address operation. It can be:
+* - NAND_VALID_ADDRESS: When the new address is valid address
+* - NAND_INVALID_ADDRESS: When the new address is invalid address
+*******************************************************************************/
+u32 FSMC_NAND_ReadSpareArea(u8 *pBuffer, NAND_ADDRESS Address, u32 NumSpareAreaToRead)
+{
+ u32 numsparearearead = 0x00, index = 0x00, addressstatus = NAND_VALID_ADDRESS;
+ u32 status = NAND_READY, size = 0x00;
+
+ while((NumSpareAreaToRead != 0x0) && (addressstatus == NAND_VALID_ADDRESS))
+ {
+ /* Page Read command and page address */
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = NAND_CMD_AREA_C;
+
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = 0x00;
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_1st_CYCLE(ROW_ADDRESS);
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_2nd_CYCLE(ROW_ADDRESS);
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_3rd_CYCLE(ROW_ADDRESS);
+
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = NAND_CMD_AREA_TRUE1;
+
+ /* Data Read */
+ size = NAND_SPARE_AREA_SIZE + (NAND_SPARE_AREA_SIZE * numsparearearead);
+
+ /* Get Data into Buffer */
+ for ( ;index < size; index++)
+ {
+ pBuffer[index] = *(vu8 *)(Bank_NAND_ADDR | DATA_AREA);
+ }
+
+ numsparearearead++;
+
+ NumSpareAreaToRead--;
+
+ /* Calculate page address */
+ addressstatus = FSMC_NAND_AddressIncrement(&Address);
+ }
+
+ status = FSMC_NAND_GetStatus();
+
+ return (status | addressstatus);
+}
+
+/******************************************************************************
+* Function Name : FSMC_NAND_EraseBlock
+* Description : This routine erase complete block from NAND FLASH
+* Input : - Address: Any address into block to be erased
+* Output : None
+* Return : New status of the NAND operation. This parameter can be:
+* - NAND_TIMEOUT_ERROR: when the previous operation generate
+* a Timeout error
+* - NAND_READY: when memory is ready for the next operation
+*******************************************************************************/
+u32 FSMC_NAND_EraseBlock(NAND_ADDRESS Address)
+{
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = NAND_CMD_ERASE0;
+
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_1st_CYCLE(ROW_ADDRESS);
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_2nd_CYCLE(ROW_ADDRESS);
+ *(vu8 *)(Bank_NAND_ADDR | ADDR_AREA) = ADDR_3rd_CYCLE(ROW_ADDRESS);
+
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = NAND_CMD_ERASE1;
+
+ return (FSMC_NAND_GetStatus());
+}
+
+/******************************************************************************
+* Function Name : FSMC_NAND_Reset
+* Description : This routine reset the NAND FLASH
+* Input : None
+* Output : None
+* Return : NAND_READY
+*******************************************************************************/
+u32 FSMC_NAND_Reset(void)
+{
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = NAND_CMD_RESET;
+
+ return (NAND_READY);
+}
+
+/******************************************************************************
+* Function Name : FSMC_NAND_GetStatus
+* Description : Get the NAND operation status
+* Input : None
+* Output : None
+* Return : New status of the NAND operation. This parameter can be:
+* - NAND_TIMEOUT_ERROR: when the previous operation generate
+* a Timeout error
+* - NAND_READY: when memory is ready for the next operation
+*******************************************************************************/
+u32 FSMC_NAND_GetStatus(void)
+{
+ u32 timeout = 0x1000000, status = NAND_READY;
+
+ status = FSMC_NAND_ReadStatus();
+
+ /* Wait for a NAND operation to complete or a TIMEOUT to occur */
+ while ((status != NAND_READY) &&( timeout != 0x00))
+ {
+ status = FSMC_NAND_ReadStatus();
+ timeout --;
+ }
+
+ if(timeout == 0x00)
+ {
+ status = NAND_TIMEOUT_ERROR;
+ }
+
+ /* Return the operation status */
+ return (status);
+}
+/******************************************************************************
+* Function Name : FSMC_NAND_ReadStatus
+* Description : Reads the NAND memory status using the Read status command
+* Input : None
+* Output : None
+* Return : The status of the NAND memory. This parameter can be:
+* - NAND_BUSY: when memory is busy
+* - NAND_READY: when memory is ready for the next operation
+* - NAND_ERROR: when the previous operation gererates error
+*******************************************************************************/
+u32 FSMC_NAND_ReadStatus(void)
+{
+ u32 data = 0x00, status = NAND_BUSY;
+
+ /* Read status operation ------------------------------------ */
+ *(vu8 *)(Bank_NAND_ADDR | CMD_AREA) = NAND_CMD_STATUS;
+ data = *(vu8 *)(Bank_NAND_ADDR);
+
+ if((data & NAND_ERROR) == NAND_ERROR)
+ {
+ status = NAND_ERROR;
+ }
+ else if((data & NAND_READY) == NAND_READY)
+ {
+ status = NAND_READY;
+ }
+ else
+ {
+ status = NAND_BUSY;
+ }
+
+ return (status);
+}
+
+/******************************************************************************
+* Function Name : NAND_AddressIncrement
+* Description : Increment the NAND memory address
+* Input : - Address: address to be incremented.
+* Output : None
+* Return : The new status of the increment address operation. It can be:
+* - NAND_VALID_ADDRESS: When the new address is valid address
+* - NAND_INVALID_ADDRESS: When the new address is invalid address
+*******************************************************************************/
+u32 FSMC_NAND_AddressIncrement(NAND_ADDRESS* Address)
+{
+ u32 status = NAND_VALID_ADDRESS;
+
+ Address->Page++;
+
+ if(Address->Page == NAND_BLOCK_SIZE)
+ {
+ Address->Page = 0;
+ Address->Block++;
+
+ if(Address->Block == NAND_ZONE_SIZE)
+ {
+ Address->Block = 0;
+ Address->Zone++;
+
+ if(Address->Zone == NAND_MAX_ZONE)
+ {
+ status = NAND_INVALID_ADDRESS;
+ }
+ }
+ }
+
+ return (status);
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NAND/fsmc_nand.h b/src/stm32lib/examples/FSMC/NAND/fsmc_nand.h new file mode 100755 index 0000000..dd90682 --- /dev/null +++ b/src/stm32lib/examples/FSMC/NAND/fsmc_nand.h @@ -0,0 +1,99 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : fsmc_nand.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Header for fsmc_nand.c file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __FSMC_NAND_H
+#define __FSMC_NAND_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+typedef struct
+{
+ u8 Maker_ID;
+ u8 Device_ID;
+ u8 Third_ID;
+ u8 Fourth_ID;
+}NAND_IDTypeDef;
+
+typedef struct
+{
+ u16 Zone;
+ u16 Block;
+ u16 Page;
+} NAND_ADDRESS;
+
+/* Exported constants --------------------------------------------------------*/
+/* NAND Area definition for STM3210E-EVAL Board RevD */
+#define CMD_AREA (u32)(1<<16) /* A16 = CLE high */
+#define ADDR_AREA (u32)(1<<17) /* A17 = ALE high */
+
+#define DATA_AREA ((u32)0x00000000)
+
+/* FSMC NAND memory command */
+#define NAND_CMD_AREA_A ((u8)0x00)
+#define NAND_CMD_AREA_B ((u8)0x01)
+#define NAND_CMD_AREA_C ((u8)0x50)
+#define NAND_CMD_AREA_TRUE1 ((u8)0x30)
+
+#define NAND_CMD_WRITE0 ((u8)0x80)
+#define NAND_CMD_WRITE_TRUE1 ((u8)0x10)
+
+#define NAND_CMD_ERASE0 ((u8)0x60)
+#define NAND_CMD_ERASE1 ((u8)0xD0)
+
+#define NAND_CMD_READID ((u8)0x90)
+#define NAND_CMD_STATUS ((u8)0x70)
+#define NAND_CMD_LOCK_STATUS ((u8)0x7A)
+#define NAND_CMD_RESET ((u8)0xFF)
+
+/* NAND memory status */
+#define NAND_VALID_ADDRESS ((u32)0x00000100)
+#define NAND_INVALID_ADDRESS ((u32)0x00000200)
+#define NAND_TIMEOUT_ERROR ((u32)0x00000400)
+#define NAND_BUSY ((u32)0x00000000)
+#define NAND_ERROR ((u32)0x00000001)
+#define NAND_READY ((u32)0x00000040)
+
+/* FSMC NAND memory parameters */
+#define NAND_PAGE_SIZE ((u16)0x0200) /* 512 bytes per page w/o Spare Area */
+#define NAND_BLOCK_SIZE ((u16)0x0020) /* 32x512 bytes pages per block */
+#define NAND_ZONE_SIZE ((u16)0x0400) /* 1024 Block per zone */
+#define NAND_SPARE_AREA_SIZE ((u16)0x0010) /* last 16 bytes as spare area */
+#define NAND_MAX_ZONE ((u16)0x0004) /* 4 zones of 1024 block */
+
+/* FSMC NAND memory address computation */
+#define ADDR_1st_CYCLE(ADDR) (u8)((ADDR)& 0xFF) /* 1st addressing cycle */
+#define ADDR_2nd_CYCLE(ADDR) (u8)(((ADDR)& 0xFF00) >> 8) /* 2nd addressing cycle */
+#define ADDR_3rd_CYCLE(ADDR) (u8)(((ADDR)& 0xFF0000) >> 16) /* 3rd addressing cycle */
+#define ADDR_4th_CYCLE(ADDR) (u8)(((ADDR)& 0xFF000000) >> 24) /* 4th addressing cycle */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void FSMC_NAND_Init(void);
+void FSMC_NAND_ReadID(NAND_IDTypeDef* NAND_ID);
+u32 FSMC_NAND_WriteSmallPage(u8 *pBuffer, NAND_ADDRESS Address, u32 NumPageToWrite);
+u32 FSMC_NAND_ReadSmallPage (u8 *pBuffer, NAND_ADDRESS Address, u32 NumPageToRead);
+u32 FSMC_NAND_WriteSpareArea(u8 *pBuffer, NAND_ADDRESS Address, u32 NumSpareAreaTowrite);
+u32 FSMC_NAND_ReadSpareArea(u8 *pBuffer, NAND_ADDRESS Address, u32 NumSpareAreaToRead);
+u32 FSMC_NAND_EraseBlock(NAND_ADDRESS Address);
+u32 FSMC_NAND_Reset(void);
+u32 FSMC_NAND_GetStatus(void);
+u32 FSMC_NAND_ReadStatus(void);
+u32 FSMC_NAND_AddressIncrement(NAND_ADDRESS* Address);
+
+#endif /* __FSMC_NAND_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NAND/main.c b/src/stm32lib/examples/FSMC/NAND/main.c new file mode 100755 index 0000000..26ac17c --- /dev/null +++ b/src/stm32lib/examples/FSMC/NAND/main.c @@ -0,0 +1,247 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+/* Includes ------------------------------------------------------------------*/
+#include "fsmc_nand.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define BUFFER_SIZE 0x400
+#define NAND_ST_MakerID 0x20
+#define NAND_ST_DeviceID 0x76
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+NAND_IDTypeDef NAND_ID;
+GPIO_InitTypeDef GPIO_InitStructure;
+NAND_ADDRESS WriteReadAddr;
+
+u8 TxBuffer[BUFFER_SIZE], RxBuffer[BUFFER_SIZE];
+
+ErrorStatus HSEStartUpStatus;
+vu32 PageNumber = 2, WriteReadStatus = 0, status= 0;
+u32 j = 0;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+void Fill_Buffer(u8 *pBuffer, u16 BufferLenght, u32 Offset);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* PF.06, PF.07 and PF.08 config to drive LD1, LD2 and LD3 *****************/
+ /* Enable GPIOF clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOF, ENABLE);
+
+ /* Configure PF.06, PF.07 and PF.08 as Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIOF, &GPIO_InitStructure);
+
+ /* Enable the FSMC Clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, ENABLE);
+
+ /* FSMC Initialization */
+ FSMC_NAND_Init();
+
+ /* NAND read ID command */
+ FSMC_NAND_ReadID(&NAND_ID);
+
+ /* Verify the NAND ID */
+ if((NAND_ID.Maker_ID == NAND_ST_MakerID) && (NAND_ID.Device_ID == NAND_ST_DeviceID))
+ {
+
+ /* NAND memory address to write to */
+ WriteReadAddr.Zone = 0x00;
+ WriteReadAddr.Block = 0x00;
+ WriteReadAddr.Page = 0x00;
+
+ /* Erase the NAND first Block */
+ status = FSMC_NAND_EraseBlock(WriteReadAddr);
+
+ /* Write data to FSMC NAND memory */
+ /* Fill the buffer to send */
+ Fill_Buffer(TxBuffer, BUFFER_SIZE , 0x66);
+
+ status = FSMC_NAND_WriteSmallPage(TxBuffer, WriteReadAddr, PageNumber);
+
+ /* Read back the written data */
+ status = FSMC_NAND_ReadSmallPage (RxBuffer, WriteReadAddr, PageNumber);
+
+ /* Verify the written data */
+ for(j = 0; j < BUFFER_SIZE; j++)
+ {
+ if(TxBuffer[j] != RxBuffer[j])
+ {
+ WriteReadStatus++;
+ }
+ }
+
+ if (WriteReadStatus == 0)
+ { /* OK */
+ /* Turn on LD1 */
+ GPIO_SetBits(GPIOF, GPIO_Pin_6);
+ }
+ else
+ { /* KO */
+ /* Turn on LD2 */
+ GPIO_SetBits(GPIOF, GPIO_Pin_7);
+ }
+ }
+ else
+ {
+ /* Turn on LD3 */
+ GPIO_SetBits(GPIOF, GPIO_Pin_8);
+ }
+
+ while(1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function name : Fill_Buffer
+* Description : Fill the buffer
+* Input : - pBuffer: pointer on the Buffer to fill
+* - BufferSize: size of the buffer to fill
+* - Offset: first value to fill on the Buffer
+* Output param : None
+*******************************************************************************/
+void Fill_Buffer(u8 *pBuffer, u16 BufferLenght, u32 Offset)
+{
+ u16 IndexTmp = 0;
+
+ /* Put in global buffer same values */
+ for (IndexTmp = 0; IndexTmp < BufferLenght; IndexTmp++ )
+ {
+ pBuffer[IndexTmp] = IndexTmp + Offset;
+ }
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NAND/readme.txt b/src/stm32lib/examples/FSMC/NAND/readme.txt new file mode 100755 index 0000000..bd78bb4 --- /dev/null +++ b/src/stm32lib/examples/FSMC/NAND/readme.txt @@ -0,0 +1,56 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the FSMC NAND Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a basic example of how to use the FSMC firmware library and
+an associate driver to perform erase/read/write operations on the NAND512W3A2 memory
+mounted on STM3210E-EVAL board.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+fsmc_nand.c Driver for NAND memory
+fsmc_nand.h Header for fsmc_nand.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board RevD.
+
+Note: make sure that the Jumper 7 (JP7) is in position 1<-->2.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_fsmc.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/FSMC/NAND/stm32f10x_conf.h b/src/stm32lib/examples/FSMC/NAND/stm32f10x_conf.h new file mode 100755 index 0000000..48e488f --- /dev/null +++ b/src/stm32lib/examples/FSMC/NAND/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+#define _GPIOD
+#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NAND/stm32f10x_it.c b/src/stm32lib/examples/FSMC/NAND/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/FSMC/NAND/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NAND/stm32f10x_it.h b/src/stm32lib/examples/FSMC/NAND/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/FSMC/NAND/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR/fsmc_nor.c b/src/stm32lib/examples/FSMC/NOR/fsmc_nor.c new file mode 100755 index 0000000..f72a14c --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR/fsmc_nor.c @@ -0,0 +1,416 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : fsmc_nor.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides a set of functions needed to drive the
+* M29W128FL, M29W128GL and S29GL128P NOR memories mounted
+* on STM3210E-EVAL board.
+********************************************************************************
+* 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.
+*******************************************************************************/
+/* Includes ------------------------------------------------------------------*/
+#include "fsmc_nor.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define Bank1_NOR2_ADDR ((u32)0x64000000)
+
+/* Delay definition */
+#define BlockErase_Timeout ((u32)0x00A00000)
+#define ChipErase_Timeout ((u32)0x30000000)
+#define Program_Timeout ((u32)0x00001400)
+
+/* Private macro -------------------------------------------------------------*/
+#define ADDR_SHIFT(A) (Bank1_NOR2_ADDR + (2 * (A)))
+#define NOR_WRITE(Address, Data) (*(vu16 *)(Address) = (Data))
+
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : FSMC_NOR_Init
+* Description : Configures the FSMC and GPIOs to interface with the NOR memory.
+* This function must be called before any write/read operation
+* on the NOR.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NOR_Init(void)
+{
+ FSMC_NORSRAMInitTypeDef FSMC_NORSRAMInitStructure;
+ FSMC_NORSRAMTimingInitTypeDef p;
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD | RCC_APB2Periph_GPIOE |
+ RCC_APB2Periph_GPIOF | RCC_APB2Periph_GPIOG, ENABLE);
+
+ /*-- GPIO Configuration ------------------------------------------------------*/
+ /* NOR Data lines configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_8 | GPIO_Pin_9 |
+ GPIO_Pin_10 | GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10 |
+ GPIO_Pin_11 | GPIO_Pin_12 | GPIO_Pin_13 |
+ GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_Init(GPIOE, &GPIO_InitStructure);
+
+ /* NOR Address lines configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3 |
+ GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_12 | GPIO_Pin_13 |
+ GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_Init(GPIOF, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 |
+ GPIO_Pin_3 | GPIO_Pin_4 | GPIO_Pin_5;
+ GPIO_Init(GPIOG, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12 | GPIO_Pin_13;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3 | GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_6;
+ GPIO_Init(GPIOE, &GPIO_InitStructure);
+
+ /* NOE and NWE configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 | GPIO_Pin_5;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ /* NE2 configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
+ GPIO_Init(GPIOG, &GPIO_InitStructure);
+
+ /*-- FSMC Configuration ----------------------------------------------------*/
+ p.FSMC_AddressSetupTime = 0x05;
+ p.FSMC_AddressHoldTime = 0x00;
+ p.FSMC_DataSetupTime = 0x07;
+ p.FSMC_BusTurnAroundDuration = 0x00;
+ p.FSMC_CLKDivision = 0x00;
+ p.FSMC_DataLatency = 0x00;
+ p.FSMC_AccessMode = FSMC_AccessMode_B;
+
+ FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2;
+ FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_NOR;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
+ FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+ FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+ FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_AsyncWait = FSMC_AsyncWait_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p;
+ FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p;
+
+ FSMC_NORSRAMInit(&FSMC_NORSRAMInitStructure);
+
+ /* Enable FSMC Bank1_NOR Bank */
+ FSMC_NORSRAMCmd(FSMC_Bank1_NORSRAM2, ENABLE);
+}
+
+/******************************************************************************
+* Function Name : FSMC_NOR_ReadID
+* Description : Reads NOR memory's Manufacturer and Device Code.
+* Input : - NOR_ID: pointer to a NOR_IDTypeDef structure which will hold
+* the Manufacturer and Device Code.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NOR_ReadID(NOR_IDTypeDef* NOR_ID)
+{
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x0090);
+
+ NOR_ID->Manufacturer_Code = *(vu16 *) ADDR_SHIFT(0x0000);
+ NOR_ID->Device_Code1 = *(vu16 *) ADDR_SHIFT(0x0001);
+ NOR_ID->Device_Code2 = *(vu16 *) ADDR_SHIFT(0x000E);
+ NOR_ID->Device_Code3 = *(vu16 *) ADDR_SHIFT(0x000F);
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NOR_EraseBlock
+* Description : Erases the specified Nor memory block.
+* Input : - BlockAddr: address of the block to erase.
+* Output : None
+* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
+* or NOR_TIMEOUT
+*******************************************************************************/
+NOR_Status FSMC_NOR_EraseBlock(u32 BlockAddr)
+{
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x0080);
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+ NOR_WRITE((Bank1_NOR2_ADDR + BlockAddr), 0x30);
+
+ return (FSMC_NOR_GetStatus(BlockErase_Timeout));
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NOR_EraseChip
+* Description : Erases the entire chip.
+* Input : None
+* Output : None
+* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
+* or NOR_TIMEOUT
+*******************************************************************************/
+NOR_Status FSMC_NOR_EraseChip(void)
+{
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x0080);
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x0010);
+
+ return (FSMC_NOR_GetStatus(ChipErase_Timeout));
+}
+
+/******************************************************************************
+* Function Name : FSMC_NOR_WriteHalfWord
+* Description : Writes a half-word to the NOR memory.
+* Input : - WriteAddr : NOR memory internal address to write to.
+* - Data : Data to write.
+* Output : None
+* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
+* or NOR_TIMEOUT
+*******************************************************************************/
+NOR_Status FSMC_NOR_WriteHalfWord(u32 WriteAddr, u16 Data)
+{
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00A0);
+ NOR_WRITE((Bank1_NOR2_ADDR + WriteAddr), Data);
+
+ return (FSMC_NOR_GetStatus(Program_Timeout));
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NOR_WriteBuffer
+* Description : Writes a half-word buffer to the FSMC NOR memory.
+* Input : - pBuffer : pointer to buffer.
+* - WriteAddr : NOR memory internal address from which the data
+* will be written.
+* - NumHalfwordToWrite : number of Half words to write.
+* Output : None
+* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
+* or NOR_TIMEOUT
+*******************************************************************************/
+NOR_Status FSMC_NOR_WriteBuffer(u16* pBuffer, u32 WriteAddr, u32 NumHalfwordToWrite)
+{
+ NOR_Status status = NOR_ONGOING;
+
+ do
+ {
+ /* Transfer data to the memory */
+ status = FSMC_NOR_WriteHalfWord(WriteAddr, *pBuffer++);
+ WriteAddr = WriteAddr + 2;
+ NumHalfwordToWrite--;
+ }
+ while((status == NOR_SUCCESS) && (NumHalfwordToWrite != 0));
+
+ return (status);
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NOR_ProgramBuffer
+* Description : Writes a half-word buffer to the FSMC NOR memory. This function
+* must be used only with S29GL128P NOR memory.
+* Input : - pBuffer : pointer to buffer.
+* - WriteAddr: NOR memory internal address from which the data
+* will be written.
+* - NumHalfwordToWrite: number of Half words to write.
+* The maximum allowed value is 32 Half words (64 bytes).
+* Output : None
+* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
+* or NOR_TIMEOUT
+*******************************************************************************/
+NOR_Status FSMC_NOR_ProgramBuffer(u16* pBuffer, u32 WriteAddr, u32 NumHalfwordToWrite)
+{
+ u32 lastloadedaddress = 0x00;
+ u32 currentaddress = 0x00;
+ u32 endaddress = 0x00;
+
+ /* Initialize variables */
+ currentaddress = WriteAddr;
+ endaddress = WriteAddr + NumHalfwordToWrite - 1;
+ lastloadedaddress = WriteAddr;
+
+ /* Issue unlock command sequence */
+ NOR_WRITE(ADDR_SHIFT(0x00555), 0x00AA);
+
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+
+ /* Write Write Buffer Load Command */
+ NOR_WRITE(ADDR_SHIFT(WriteAddr), 0x0025);
+ NOR_WRITE(ADDR_SHIFT(WriteAddr), (NumHalfwordToWrite - 1));
+
+ /* Load Data into NOR Buffer */
+ while(currentaddress <= endaddress)
+ {
+ /* Store last loaded address & data value (for polling) */
+ lastloadedaddress = currentaddress;
+
+ NOR_WRITE(ADDR_SHIFT(currentaddress), *pBuffer++);
+ currentaddress += 1;
+ }
+
+ NOR_WRITE(ADDR_SHIFT(lastloadedaddress), 0x29);
+
+ return(FSMC_NOR_GetStatus(Program_Timeout));
+}
+
+/******************************************************************************
+* Function Name : FSMC_NOR_ReadHalfWord
+* Description : Reads a half-word from the NOR memory.
+* Input : - ReadAddr : NOR memory internal address to read from.
+* Output : None
+* Return : Half-word read from the NOR memory
+*******************************************************************************/
+u16 FSMC_NOR_ReadHalfWord(u32 ReadAddr)
+{
+ NOR_WRITE(ADDR_SHIFT(0x00555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x002AA), 0x0055);
+ NOR_WRITE((Bank1_NOR2_ADDR + ReadAddr), 0x00F0 );
+
+ return (*(vu16 *)((Bank1_NOR2_ADDR + ReadAddr)));
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NOR_ReadBuffer
+* Description : Reads a block of data from the FSMC NOR memory.
+* Input : - pBuffer : pointer to the buffer that receives the data read
+* from the NOR memory.
+* - ReadAddr : NOR memory internal address to read from.
+* - NumHalfwordToRead : number of Half word to read.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NOR_ReadBuffer(u16* pBuffer, u32 ReadAddr, u32 NumHalfwordToRead)
+{
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+ NOR_WRITE((Bank1_NOR2_ADDR + ReadAddr), 0x00F0);
+
+ for(; NumHalfwordToRead != 0x00; NumHalfwordToRead--) /* while there is data to read */
+ {
+ /* Read a Halfword from the NOR */
+ *pBuffer++ = *(vu16 *)((Bank1_NOR2_ADDR + ReadAddr));
+ ReadAddr = ReadAddr + 2;
+ }
+}
+
+/******************************************************************************
+* Function Name : FSMC_NOR_ReturnToReadMode
+* Description : Returns the NOR memory to Read mode.
+* Input : None
+* Output : None
+* Return : NOR_SUCCESS
+*******************************************************************************/
+NOR_Status FSMC_NOR_ReturnToReadMode(void)
+{
+ NOR_WRITE(Bank1_NOR2_ADDR, 0x00F0);
+
+ return (NOR_SUCCESS);
+}
+
+/******************************************************************************
+* Function Name : FSMC_NOR_Reset
+* Description : Returns the NOR memory to Read mode and resets the errors in
+* the NOR memory Status Register.
+* Input : None
+* Output : None
+* Return : NOR_SUCCESS
+*******************************************************************************/
+NOR_Status FSMC_NOR_Reset(void)
+{
+ NOR_WRITE(ADDR_SHIFT(0x00555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x002AA), 0x0055);
+ NOR_WRITE(Bank1_NOR2_ADDR, 0x00F0);
+
+ return (NOR_SUCCESS);
+}
+
+/******************************************************************************
+* Function Name : FSMC_NOR_GetStatus
+* Description : Returns the NOR operation status.
+* Input : - Timeout: NOR progamming Timeout
+* Output : None
+* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
+* or NOR_TIMEOUT
+*******************************************************************************/
+NOR_Status FSMC_NOR_GetStatus(u32 Timeout)
+{
+ u16 val1 = 0x00, val2 = 0x00;
+ NOR_Status status = NOR_ONGOING;
+ u32 timeout = Timeout;
+
+ /* Poll on NOR memory Ready/Busy signal ------------------------------------*/
+ while((GPIO_ReadInputDataBit(GPIOD, GPIO_Pin_6) != RESET) && (timeout > 0))
+ {
+ timeout--;
+ }
+
+ timeout = Timeout;
+
+ while((GPIO_ReadInputDataBit(GPIOD, GPIO_Pin_6) == RESET) && (timeout > 0))
+ {
+ timeout--;
+ }
+
+ /* Get the NOR memory operation status -------------------------------------*/
+ while((Timeout != 0x00) && (status != NOR_SUCCESS))
+ {
+ Timeout--;
+
+ /* Read DQ6 and DQ5 */
+ val1 = *(vu16 *)(Bank1_NOR2_ADDR);
+ val2 = *(vu16 *)(Bank1_NOR2_ADDR);
+
+ /* If DQ6 did not toggle between the two reads then return NOR_Success */
+ if((val1 & 0x0040) == (val2 & 0x0040))
+ {
+ return NOR_SUCCESS;
+ }
+
+ if((val1 & 0x0020) != 0x0020)
+ {
+ status = NOR_ONGOING;
+ }
+
+ val1 = *(vu16 *)(Bank1_NOR2_ADDR);
+ val2 = *(vu16 *)(Bank1_NOR2_ADDR);
+
+ if((val1 & 0x0040) == (val2 & 0x0040))
+ {
+ return NOR_SUCCESS;
+ }
+ else if((val1 & 0x0020) == 0x0020)
+ {
+ return NOR_ERROR;
+ }
+ }
+
+ if(Timeout == 0x00)
+ {
+ status = NOR_TIMEOUT;
+ }
+
+ /* Return the operation status */
+ return (status);
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR/fsmc_nor.h b/src/stm32lib/examples/FSMC/NOR/fsmc_nor.h new file mode 100755 index 0000000..264f231 --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR/fsmc_nor.h @@ -0,0 +1,58 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : fsmc_nor.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Header for fsmc_nor.c file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __FSMC_NOR_H
+#define __FSMC_NOR_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+typedef struct
+{
+ u16 Manufacturer_Code;
+ u16 Device_Code1;
+ u16 Device_Code2;
+ u16 Device_Code3;
+}NOR_IDTypeDef;
+
+/* NOR Status */
+typedef enum
+{
+ NOR_SUCCESS = 0,
+ NOR_ONGOING,
+ NOR_ERROR,
+ NOR_TIMEOUT
+}NOR_Status;
+
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void FSMC_NOR_Init(void);
+void FSMC_NOR_ReadID(NOR_IDTypeDef* NOR_ID);
+NOR_Status FSMC_NOR_EraseBlock(u32 BlockAddr);
+NOR_Status FSMC_NOR_EraseChip(void);
+NOR_Status FSMC_NOR_WriteHalfWord(u32 WriteAddr, u16 Data);
+NOR_Status FSMC_NOR_WriteBuffer(u16* pBuffer, u32 WriteAddr, u32 NumHalfwordToWrite);
+NOR_Status FSMC_NOR_ProgramBuffer(u16* pBuffer, u32 WriteAddr, u32 NumHalfwordToWrite);
+u16 FSMC_NOR_ReadHalfWord(u32 ReadAddr);
+void FSMC_NOR_ReadBuffer(u16* pBuffer, u32 ReadAddr, u32 NumHalfwordToRead);
+NOR_Status FSMC_NOR_ReturnToReadMode(void);
+NOR_Status FSMC_NOR_Reset(void);
+NOR_Status FSMC_NOR_GetStatus(u32 Timeout);
+
+#endif /* __FSMC_NOR_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR/main.c b/src/stm32lib/examples/FSMC/NOR/main.c new file mode 100755 index 0000000..508fc6f --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR/main.c @@ -0,0 +1,233 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "fsmc_nor.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define BUFFER_SIZE 0x400
+#define WRITE_READ_ADDR 0x8000
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+GPIO_InitTypeDef GPIO_InitStructure;
+ErrorStatus HSEStartUpStatus;
+
+u16 TxBuffer[BUFFER_SIZE];
+u16 RxBuffer[BUFFER_SIZE];
+u32 WriteReadStatus = 0, Index = 0;
+NOR_IDTypeDef NOR_ID;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+
+void Fill_Buffer(u16 *pBuffer, u16 BufferLenght, u32 Offset);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* PF.06 and PF.07 config to drive LD1 and LD2 *****************************/
+ /* Enable GPIOF clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOF, ENABLE);
+
+ /* Configure PF.06 and PF.07 as Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIOF, &GPIO_InitStructure);
+
+ /* Write/read to/from FSMC SRAM memory *************************************/
+ /* Enable the FSMC Clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, ENABLE);
+
+ /* Configure FSMC Bank1 NOR/SRAM2 */
+ FSMC_NOR_Init();
+
+ /* Read NOR memory ID */
+ FSMC_NOR_ReadID(&NOR_ID);
+
+ FSMC_NOR_ReturnToReadMode();
+
+ /* Erase the NOR memory block to write on */
+ FSMC_NOR_EraseBlock(WRITE_READ_ADDR);
+
+ /* Write data to FSMC NOR memory */
+ /* Fill the buffer to send */
+ Fill_Buffer(TxBuffer, BUFFER_SIZE, 0x3210);
+ FSMC_NOR_WriteBuffer(TxBuffer, WRITE_READ_ADDR, BUFFER_SIZE);
+
+ /* Read data from FSMC NOR memory */
+ FSMC_NOR_ReadBuffer(RxBuffer, WRITE_READ_ADDR, BUFFER_SIZE);
+
+ /* Read back NOR memory and check content correctness */
+ for (Index = 0x00; (Index < BUFFER_SIZE) && (WriteReadStatus == 0); Index++)
+ {
+ if (RxBuffer[Index] != TxBuffer[Index])
+ {
+ WriteReadStatus = Index + 1;
+ }
+ }
+
+ if (WriteReadStatus == 0)
+ { /* OK */
+ /* Turn on LD1 */
+ GPIO_SetBits(GPIOF, GPIO_Pin_6);
+ }
+ else
+ { /* KO */
+ /* Turn on LD2 */
+ GPIO_SetBits(GPIOF, GPIO_Pin_7);
+ }
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function name : Fill_Buffer
+* Description : Fill the global buffer
+* Input : - pBuffer: pointer on the Buffer to fill
+* - BufferSize: size of the buffer to fill
+* - Offset: first value to fill on the Buffer
+* Output param : None
+*******************************************************************************/
+void Fill_Buffer(u16 *pBuffer, u16 BufferLenght, u32 Offset)
+{
+ u16 IndexTmp = 0;
+
+ /* Put in global buffer same values */
+ for (IndexTmp = 0; IndexTmp < BufferLenght; IndexTmp++ )
+ {
+ pBuffer[IndexTmp] = IndexTmp + Offset;
+ }
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR/readme.txt b/src/stm32lib/examples/FSMC/NOR/readme.txt new file mode 100755 index 0000000..79deab2 --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR/readme.txt @@ -0,0 +1,55 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the FSMC NOR Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+
+This example provides a basic example of how to use the FSMC firmware library and
+an associate driver to perform erase/read/write operations on the M29W128FL,
+M29W128GL or S29GL128P NOR memories mounted on the STM3210E-EVAL board.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+fsmc_nor.c Driver for NOR memory
+fsmc_nor.h Header for fsmc_nor.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_fsmc.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/FSMC/NOR/stm32f10x_conf.h b/src/stm32lib/examples/FSMC/NOR/stm32f10x_conf.h new file mode 100755 index 0000000..48e488f --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+#define _GPIOD
+#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR/stm32f10x_it.c b/src/stm32lib/examples/FSMC/NOR/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR/stm32f10x_it.h b/src/stm32lib/examples/FSMC/NOR/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/FLASH_NOR.ini b/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/FLASH_NOR.ini new file mode 100755 index 0000000..62440b9 --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/FLASH_NOR.ini @@ -0,0 +1,38 @@ +/******************************************************************************/
+/* FLASH_NOR.ini: NOR Initialization File */
+/******************************************************************************/
+// <<< Use Configuration Wizard in Context Menu >>> //
+/******************************************************************************/
+/* This file is part of the uVision/ARM development tools. */
+/* Copyright (c) 2005-2006 Keil Software. All rights reserved. */
+/* This software may only be used under the terms of a valid, current, */
+/* end user licence from KEIL for a compatible version of KEIL software */
+/* development tools. Nothing else gives you the right to use this software. */
+/******************************************************************************/
+
+FUNC void Setup(void) {
+
+ _WDWORD(0x40021014, 0x00000114); // FSMC clock enable
+ _WDWORD(0x40021018, 0x000001FD); // GPIOD~G clock enable
+
+ _WDWORD(0x40011400, 0x44BB44BB); // GPIOD config
+ _WDWORD(0x40011404, 0xBBBBBBBB); // GPIOD config
+
+ _WDWORD(0x40011800, 0xBBBBB444); // GPIOE config
+ _WDWORD(0x40011804, 0xBBBBBBBB); // GPIOE config
+
+ _WDWORD(0x40011C00, 0x44BBBBBB); // GPIOF config
+ _WDWORD(0x40011C04, 0xBBBB4444); // GPIOF config
+
+ _WDWORD(0x40012000, 0x44BBBBBB); // GPIOG config
+ _WDWORD(0x40012004, 0x444444B4); // GPIOG config
+
+ _WDWORD(0xA0000000, 0x000030DB); // FSMC config
+ _WDWORD(0xA0000008, 0x00001059); // FSMC config
+ _WDWORD(0xA000000C, 0x10000705); // FSMC config
+ _WDWORD(0xA0000104, 0x0FFFFFFF); // FSMC config
+}
+
+Setup();
+
+
diff --git a/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/STM3210E-EVAL_NOR.FLM b/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/STM3210E-EVAL_NOR.FLM Binary files differnew file mode 100755 index 0000000..f8be719 --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/STM3210E-EVAL_NOR.FLM diff --git a/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/main.c b/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/main.c new file mode 100755 index 0000000..1c7c69d --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/main.c @@ -0,0 +1,112 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+GPIO_InitTypeDef GPIO_InitStructure;
+
+/* Private function prototypes -----------------------------------------------*/
+void Delay(vu32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* Enable GPIOF clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOF, ENABLE);
+
+ /* Configure IO connected to LD1, LD2, LD3 and LD4 leds */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOF, &GPIO_InitStructure);
+
+ while (1)
+ {
+ /* Turn on LD1 */
+ GPIO_SetBits(GPIOF, GPIO_Pin_6);
+ /* Insert delay */
+ Delay(0xAFFFF);
+
+ /* Turn on LD2 and LD3 */
+ GPIO_SetBits(GPIOF, GPIO_Pin_7 | GPIO_Pin_8);
+ /* Turn off LD1 */
+ GPIO_ResetBits(GPIOF, GPIO_Pin_6);
+ /* Insert delay */
+ Delay(0xAFFFF);
+
+ /* Turn on LD4 */
+ GPIO_SetBits(GPIOF, GPIO_Pin_9);
+ /* Turn off LD2 and LD3 */
+ GPIO_ResetBits(GPIOF, GPIO_Pin_8 | GPIO_Pin_7);
+ /* Insert delay */
+ Delay(0xAFFFF);
+
+ /* Turn off LD4 */
+ GPIO_ResetBits(GPIOF, GPIO_Pin_9);
+ }
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for(; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/readme.txt b/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/readme.txt new file mode 100755 index 0000000..709393c --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/readme.txt @@ -0,0 +1,92 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the binary directory.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Description
+===================
+This directory contains a set of sources files that build the application to be
+loaded into the NOR memory mounted on STM3210E-EVAL board.
+
+The GPIO IOToggle example provided within the STM32F10x Firmware library is used
+as illustration. In this example four LEDs connected to the PF.06, PF.07, PF.08
+and PF.09 pins are toggled in an infinite loop.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+FLASH_NOR.ini NOR Initialization File for RVMDK toolchain.
+STM3210E-EVAL_NOR.FLM STM3210E-EVAL board NOR flasher for RVMDK toolchain.
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board and can be
+easily tailored to any other hardware.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files:
+ + RVMDK
+ - copy "STM3210E-EVAL_NOR.FLM" file under "C:\Keil\ARM\Flash" directory
+ - in Project->Options->Target window, select 'ROM1', enter 0x64000000 as
+ start address with size of 0x1000000 ans check "Startup" option (IROM1 must be un-checked)
+ - in Project->Options->Linker window, enter 0x64000000 as R/O base address
+ - in Project->Options->Utilities window, select "Use Target Driver for Flash Programming"
+ - Click on 'Settings' button then select "STM3210E_EVAL NOR Flash" as
+ Programming Algorithms (start:0x64000000, size:0x1000000)
+ - in "Init File" select "FLASH_NOR.ini" provided within this example directory
+
+ + EWARM4
+ - use "lnkarm_nor.xcl" as linker file
+ - in project->options ->debugger-> setup , the "run to main" option should be
+ un-checked
+ - in project->options ->debugger->download click on "edit" button("Use flash
+ loader(s)" option must be checked)
+ - select the default flash loader then click on "edit" button
+ - check the "Relocate" option and enter 0x64000000 as Base address
+ - check "override default flash loader path" option and use "FlashSTM32F10x_NOR.d79"
+ as flash loader
+
+ + EWARM5
+ - use "stm32f10x_nor.icf" as linker file
+ - in project->options ->debugger-> setup , the "run to main" option should be
+ un-checked
+ - in project->options ->debugger->download click on "edit" button("Use flash
+ loader(s)" option must be checked)
+ - select the default flash loader then click on "edit" button
+ - check the "Relocate" option and enter 0x64000000 as Base address
+ - check "override default flash loader path" option and use "FlashSTM32F10x_NOR.out"
+ as flash loader
+
+ + HiTOP
+ - in project->settings->project->tool settings ->linker, use "linknor.lnk"
+ as linker file.
+ - run the script Flash_Nor (click on the button Flash_Nor from the toolbar menu)
+ before loading the image into target.
+
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into NOR memory
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/stm32f10x_conf.h b/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/stm32f10x_conf.h new file mode 100755 index 0000000..53aa202 --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+//#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz */
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/stm32f10x_it.c b/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/stm32f10x_it.h b/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR_CodeExecute/binary/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR_CodeExecute/fsmc_nor.c b/src/stm32lib/examples/FSMC/NOR_CodeExecute/fsmc_nor.c new file mode 100755 index 0000000..f72a14c --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR_CodeExecute/fsmc_nor.c @@ -0,0 +1,416 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : fsmc_nor.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides a set of functions needed to drive the
+* M29W128FL, M29W128GL and S29GL128P NOR memories mounted
+* on STM3210E-EVAL board.
+********************************************************************************
+* 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.
+*******************************************************************************/
+/* Includes ------------------------------------------------------------------*/
+#include "fsmc_nor.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define Bank1_NOR2_ADDR ((u32)0x64000000)
+
+/* Delay definition */
+#define BlockErase_Timeout ((u32)0x00A00000)
+#define ChipErase_Timeout ((u32)0x30000000)
+#define Program_Timeout ((u32)0x00001400)
+
+/* Private macro -------------------------------------------------------------*/
+#define ADDR_SHIFT(A) (Bank1_NOR2_ADDR + (2 * (A)))
+#define NOR_WRITE(Address, Data) (*(vu16 *)(Address) = (Data))
+
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : FSMC_NOR_Init
+* Description : Configures the FSMC and GPIOs to interface with the NOR memory.
+* This function must be called before any write/read operation
+* on the NOR.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NOR_Init(void)
+{
+ FSMC_NORSRAMInitTypeDef FSMC_NORSRAMInitStructure;
+ FSMC_NORSRAMTimingInitTypeDef p;
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD | RCC_APB2Periph_GPIOE |
+ RCC_APB2Periph_GPIOF | RCC_APB2Periph_GPIOG, ENABLE);
+
+ /*-- GPIO Configuration ------------------------------------------------------*/
+ /* NOR Data lines configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_8 | GPIO_Pin_9 |
+ GPIO_Pin_10 | GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10 |
+ GPIO_Pin_11 | GPIO_Pin_12 | GPIO_Pin_13 |
+ GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_Init(GPIOE, &GPIO_InitStructure);
+
+ /* NOR Address lines configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3 |
+ GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_12 | GPIO_Pin_13 |
+ GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_Init(GPIOF, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 |
+ GPIO_Pin_3 | GPIO_Pin_4 | GPIO_Pin_5;
+ GPIO_Init(GPIOG, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12 | GPIO_Pin_13;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3 | GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_6;
+ GPIO_Init(GPIOE, &GPIO_InitStructure);
+
+ /* NOE and NWE configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 | GPIO_Pin_5;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ /* NE2 configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
+ GPIO_Init(GPIOG, &GPIO_InitStructure);
+
+ /*-- FSMC Configuration ----------------------------------------------------*/
+ p.FSMC_AddressSetupTime = 0x05;
+ p.FSMC_AddressHoldTime = 0x00;
+ p.FSMC_DataSetupTime = 0x07;
+ p.FSMC_BusTurnAroundDuration = 0x00;
+ p.FSMC_CLKDivision = 0x00;
+ p.FSMC_DataLatency = 0x00;
+ p.FSMC_AccessMode = FSMC_AccessMode_B;
+
+ FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2;
+ FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_NOR;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
+ FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+ FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+ FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_AsyncWait = FSMC_AsyncWait_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p;
+ FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p;
+
+ FSMC_NORSRAMInit(&FSMC_NORSRAMInitStructure);
+
+ /* Enable FSMC Bank1_NOR Bank */
+ FSMC_NORSRAMCmd(FSMC_Bank1_NORSRAM2, ENABLE);
+}
+
+/******************************************************************************
+* Function Name : FSMC_NOR_ReadID
+* Description : Reads NOR memory's Manufacturer and Device Code.
+* Input : - NOR_ID: pointer to a NOR_IDTypeDef structure which will hold
+* the Manufacturer and Device Code.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NOR_ReadID(NOR_IDTypeDef* NOR_ID)
+{
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x0090);
+
+ NOR_ID->Manufacturer_Code = *(vu16 *) ADDR_SHIFT(0x0000);
+ NOR_ID->Device_Code1 = *(vu16 *) ADDR_SHIFT(0x0001);
+ NOR_ID->Device_Code2 = *(vu16 *) ADDR_SHIFT(0x000E);
+ NOR_ID->Device_Code3 = *(vu16 *) ADDR_SHIFT(0x000F);
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NOR_EraseBlock
+* Description : Erases the specified Nor memory block.
+* Input : - BlockAddr: address of the block to erase.
+* Output : None
+* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
+* or NOR_TIMEOUT
+*******************************************************************************/
+NOR_Status FSMC_NOR_EraseBlock(u32 BlockAddr)
+{
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x0080);
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+ NOR_WRITE((Bank1_NOR2_ADDR + BlockAddr), 0x30);
+
+ return (FSMC_NOR_GetStatus(BlockErase_Timeout));
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NOR_EraseChip
+* Description : Erases the entire chip.
+* Input : None
+* Output : None
+* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
+* or NOR_TIMEOUT
+*******************************************************************************/
+NOR_Status FSMC_NOR_EraseChip(void)
+{
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x0080);
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x0010);
+
+ return (FSMC_NOR_GetStatus(ChipErase_Timeout));
+}
+
+/******************************************************************************
+* Function Name : FSMC_NOR_WriteHalfWord
+* Description : Writes a half-word to the NOR memory.
+* Input : - WriteAddr : NOR memory internal address to write to.
+* - Data : Data to write.
+* Output : None
+* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
+* or NOR_TIMEOUT
+*******************************************************************************/
+NOR_Status FSMC_NOR_WriteHalfWord(u32 WriteAddr, u16 Data)
+{
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00A0);
+ NOR_WRITE((Bank1_NOR2_ADDR + WriteAddr), Data);
+
+ return (FSMC_NOR_GetStatus(Program_Timeout));
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NOR_WriteBuffer
+* Description : Writes a half-word buffer to the FSMC NOR memory.
+* Input : - pBuffer : pointer to buffer.
+* - WriteAddr : NOR memory internal address from which the data
+* will be written.
+* - NumHalfwordToWrite : number of Half words to write.
+* Output : None
+* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
+* or NOR_TIMEOUT
+*******************************************************************************/
+NOR_Status FSMC_NOR_WriteBuffer(u16* pBuffer, u32 WriteAddr, u32 NumHalfwordToWrite)
+{
+ NOR_Status status = NOR_ONGOING;
+
+ do
+ {
+ /* Transfer data to the memory */
+ status = FSMC_NOR_WriteHalfWord(WriteAddr, *pBuffer++);
+ WriteAddr = WriteAddr + 2;
+ NumHalfwordToWrite--;
+ }
+ while((status == NOR_SUCCESS) && (NumHalfwordToWrite != 0));
+
+ return (status);
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NOR_ProgramBuffer
+* Description : Writes a half-word buffer to the FSMC NOR memory. This function
+* must be used only with S29GL128P NOR memory.
+* Input : - pBuffer : pointer to buffer.
+* - WriteAddr: NOR memory internal address from which the data
+* will be written.
+* - NumHalfwordToWrite: number of Half words to write.
+* The maximum allowed value is 32 Half words (64 bytes).
+* Output : None
+* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
+* or NOR_TIMEOUT
+*******************************************************************************/
+NOR_Status FSMC_NOR_ProgramBuffer(u16* pBuffer, u32 WriteAddr, u32 NumHalfwordToWrite)
+{
+ u32 lastloadedaddress = 0x00;
+ u32 currentaddress = 0x00;
+ u32 endaddress = 0x00;
+
+ /* Initialize variables */
+ currentaddress = WriteAddr;
+ endaddress = WriteAddr + NumHalfwordToWrite - 1;
+ lastloadedaddress = WriteAddr;
+
+ /* Issue unlock command sequence */
+ NOR_WRITE(ADDR_SHIFT(0x00555), 0x00AA);
+
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+
+ /* Write Write Buffer Load Command */
+ NOR_WRITE(ADDR_SHIFT(WriteAddr), 0x0025);
+ NOR_WRITE(ADDR_SHIFT(WriteAddr), (NumHalfwordToWrite - 1));
+
+ /* Load Data into NOR Buffer */
+ while(currentaddress <= endaddress)
+ {
+ /* Store last loaded address & data value (for polling) */
+ lastloadedaddress = currentaddress;
+
+ NOR_WRITE(ADDR_SHIFT(currentaddress), *pBuffer++);
+ currentaddress += 1;
+ }
+
+ NOR_WRITE(ADDR_SHIFT(lastloadedaddress), 0x29);
+
+ return(FSMC_NOR_GetStatus(Program_Timeout));
+}
+
+/******************************************************************************
+* Function Name : FSMC_NOR_ReadHalfWord
+* Description : Reads a half-word from the NOR memory.
+* Input : - ReadAddr : NOR memory internal address to read from.
+* Output : None
+* Return : Half-word read from the NOR memory
+*******************************************************************************/
+u16 FSMC_NOR_ReadHalfWord(u32 ReadAddr)
+{
+ NOR_WRITE(ADDR_SHIFT(0x00555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x002AA), 0x0055);
+ NOR_WRITE((Bank1_NOR2_ADDR + ReadAddr), 0x00F0 );
+
+ return (*(vu16 *)((Bank1_NOR2_ADDR + ReadAddr)));
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NOR_ReadBuffer
+* Description : Reads a block of data from the FSMC NOR memory.
+* Input : - pBuffer : pointer to the buffer that receives the data read
+* from the NOR memory.
+* - ReadAddr : NOR memory internal address to read from.
+* - NumHalfwordToRead : number of Half word to read.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NOR_ReadBuffer(u16* pBuffer, u32 ReadAddr, u32 NumHalfwordToRead)
+{
+ NOR_WRITE(ADDR_SHIFT(0x0555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x02AA), 0x0055);
+ NOR_WRITE((Bank1_NOR2_ADDR + ReadAddr), 0x00F0);
+
+ for(; NumHalfwordToRead != 0x00; NumHalfwordToRead--) /* while there is data to read */
+ {
+ /* Read a Halfword from the NOR */
+ *pBuffer++ = *(vu16 *)((Bank1_NOR2_ADDR + ReadAddr));
+ ReadAddr = ReadAddr + 2;
+ }
+}
+
+/******************************************************************************
+* Function Name : FSMC_NOR_ReturnToReadMode
+* Description : Returns the NOR memory to Read mode.
+* Input : None
+* Output : None
+* Return : NOR_SUCCESS
+*******************************************************************************/
+NOR_Status FSMC_NOR_ReturnToReadMode(void)
+{
+ NOR_WRITE(Bank1_NOR2_ADDR, 0x00F0);
+
+ return (NOR_SUCCESS);
+}
+
+/******************************************************************************
+* Function Name : FSMC_NOR_Reset
+* Description : Returns the NOR memory to Read mode and resets the errors in
+* the NOR memory Status Register.
+* Input : None
+* Output : None
+* Return : NOR_SUCCESS
+*******************************************************************************/
+NOR_Status FSMC_NOR_Reset(void)
+{
+ NOR_WRITE(ADDR_SHIFT(0x00555), 0x00AA);
+ NOR_WRITE(ADDR_SHIFT(0x002AA), 0x0055);
+ NOR_WRITE(Bank1_NOR2_ADDR, 0x00F0);
+
+ return (NOR_SUCCESS);
+}
+
+/******************************************************************************
+* Function Name : FSMC_NOR_GetStatus
+* Description : Returns the NOR operation status.
+* Input : - Timeout: NOR progamming Timeout
+* Output : None
+* Return : NOR_Status:The returned value can be: NOR_SUCCESS, NOR_ERROR
+* or NOR_TIMEOUT
+*******************************************************************************/
+NOR_Status FSMC_NOR_GetStatus(u32 Timeout)
+{
+ u16 val1 = 0x00, val2 = 0x00;
+ NOR_Status status = NOR_ONGOING;
+ u32 timeout = Timeout;
+
+ /* Poll on NOR memory Ready/Busy signal ------------------------------------*/
+ while((GPIO_ReadInputDataBit(GPIOD, GPIO_Pin_6) != RESET) && (timeout > 0))
+ {
+ timeout--;
+ }
+
+ timeout = Timeout;
+
+ while((GPIO_ReadInputDataBit(GPIOD, GPIO_Pin_6) == RESET) && (timeout > 0))
+ {
+ timeout--;
+ }
+
+ /* Get the NOR memory operation status -------------------------------------*/
+ while((Timeout != 0x00) && (status != NOR_SUCCESS))
+ {
+ Timeout--;
+
+ /* Read DQ6 and DQ5 */
+ val1 = *(vu16 *)(Bank1_NOR2_ADDR);
+ val2 = *(vu16 *)(Bank1_NOR2_ADDR);
+
+ /* If DQ6 did not toggle between the two reads then return NOR_Success */
+ if((val1 & 0x0040) == (val2 & 0x0040))
+ {
+ return NOR_SUCCESS;
+ }
+
+ if((val1 & 0x0020) != 0x0020)
+ {
+ status = NOR_ONGOING;
+ }
+
+ val1 = *(vu16 *)(Bank1_NOR2_ADDR);
+ val2 = *(vu16 *)(Bank1_NOR2_ADDR);
+
+ if((val1 & 0x0040) == (val2 & 0x0040))
+ {
+ return NOR_SUCCESS;
+ }
+ else if((val1 & 0x0020) == 0x0020)
+ {
+ return NOR_ERROR;
+ }
+ }
+
+ if(Timeout == 0x00)
+ {
+ status = NOR_TIMEOUT;
+ }
+
+ /* Return the operation status */
+ return (status);
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR_CodeExecute/fsmc_nor.h b/src/stm32lib/examples/FSMC/NOR_CodeExecute/fsmc_nor.h new file mode 100755 index 0000000..264f231 --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR_CodeExecute/fsmc_nor.h @@ -0,0 +1,58 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : fsmc_nor.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Header for fsmc_nor.c file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __FSMC_NOR_H
+#define __FSMC_NOR_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+typedef struct
+{
+ u16 Manufacturer_Code;
+ u16 Device_Code1;
+ u16 Device_Code2;
+ u16 Device_Code3;
+}NOR_IDTypeDef;
+
+/* NOR Status */
+typedef enum
+{
+ NOR_SUCCESS = 0,
+ NOR_ONGOING,
+ NOR_ERROR,
+ NOR_TIMEOUT
+}NOR_Status;
+
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void FSMC_NOR_Init(void);
+void FSMC_NOR_ReadID(NOR_IDTypeDef* NOR_ID);
+NOR_Status FSMC_NOR_EraseBlock(u32 BlockAddr);
+NOR_Status FSMC_NOR_EraseChip(void);
+NOR_Status FSMC_NOR_WriteHalfWord(u32 WriteAddr, u16 Data);
+NOR_Status FSMC_NOR_WriteBuffer(u16* pBuffer, u32 WriteAddr, u32 NumHalfwordToWrite);
+NOR_Status FSMC_NOR_ProgramBuffer(u16* pBuffer, u32 WriteAddr, u32 NumHalfwordToWrite);
+u16 FSMC_NOR_ReadHalfWord(u32 ReadAddr);
+void FSMC_NOR_ReadBuffer(u16* pBuffer, u32 ReadAddr, u32 NumHalfwordToRead);
+NOR_Status FSMC_NOR_ReturnToReadMode(void);
+NOR_Status FSMC_NOR_Reset(void);
+NOR_Status FSMC_NOR_GetStatus(u32 Timeout);
+
+#endif /* __FSMC_NOR_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR_CodeExecute/main.c b/src/stm32lib/examples/FSMC/NOR_CodeExecute/main.c new file mode 100755 index 0000000..d78ec16 --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR_CodeExecute/main.c @@ -0,0 +1,171 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "fsmc_nor.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef void (*pFunction)(void);
+
+/* Private define ------------------------------------------------------------*/
+#define ApplicationAddress ((u32)0x64000000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+pFunction Jump_To_Application;
+vu32 JumpAddress;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* FSMC nOR configuration **************************************************/
+ /* Enable the FSMC Clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, ENABLE);
+
+ /* Configure FSMC Bank1 NOR/SRAM2 */
+ FSMC_NOR_Init();
+
+
+ /* Jump to code loaded in NOR memory and execute it *************************/
+ JumpAddress = *(vu32*) (ApplicationAddress + 4);
+ Jump_To_Application = (pFunction) JumpAddress;
+
+ /* Initialize user application's Stack Pointer */
+ __MSR_MSP(*(vu32*) ApplicationAddress);
+
+ Jump_To_Application();
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR_CodeExecute/readme.txt b/src/stm32lib/examples/FSMC/NOR_CodeExecute/readme.txt new file mode 100755 index 0000000..71ac2fd --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR_CodeExecute/readme.txt @@ -0,0 +1,56 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the FSMC NOR_CodeExecute Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This directory contains a set of sources files that describes how to build an
+application to be loaded into the NOR memory mounted on STM3210E-EVAL board then
+execute it from internal Flash.
+
+
+Directory contents
+==================
+ + \binary Contains a set of sources files that build the application
+ to be loaded into the NOR memory mounted on STM3210E-EVAL board.
+ + stm32f10x_conf.h Library Configuration file
+ + stm32f10x_it.c Interrupt handlers
+ + stm32f10x_it.h Header for stm32f10x_it.c
+ + main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+1. Program the NOR memory with the example provided in the \binary directory
+2. Program the internal Flash with the code that will jump to the NOR memory to execute
+ the loaded example, for this you have to:
+ - Create a project and setup all your toolchain's start-up files
+ - Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ - Link all compiled files and load your image into target memory
+ - Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/FSMC/NOR_CodeExecute/stm32f10x_conf.h b/src/stm32lib/examples/FSMC/NOR_CodeExecute/stm32f10x_conf.h new file mode 100755 index 0000000..48e488f --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR_CodeExecute/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+#define _GPIOD
+#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR_CodeExecute/stm32f10x_it.c b/src/stm32lib/examples/FSMC/NOR_CodeExecute/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR_CodeExecute/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/NOR_CodeExecute/stm32f10x_it.h b/src/stm32lib/examples/FSMC/NOR_CodeExecute/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/FSMC/NOR_CodeExecute/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/SRAM/fsmc_sram.c b/src/stm32lib/examples/FSMC/SRAM/fsmc_sram.c new file mode 100755 index 0000000..ea7d248 --- /dev/null +++ b/src/stm32lib/examples/FSMC/SRAM/fsmc_sram.c @@ -0,0 +1,161 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : fsmc_sram.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides a set of functions needed to drive the
+* IS61WV51216BLL SRAM memory mounted on STM3210E-EVAL board.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "fsmc_sram.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define Bank1_SRAM3_ADDR ((u32)0x68000000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : FSMC_SRAM_Init
+* Description : Configures the FSMC and GPIOs to interface with the SRAM memory.
+* This function must be called before any write/read operation
+* on the SRAM.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_SRAM_Init(void)
+{
+ FSMC_NORSRAMInitTypeDef FSMC_NORSRAMInitStructure;
+ FSMC_NORSRAMTimingInitTypeDef p;
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD | RCC_APB2Periph_GPIOG | RCC_APB2Periph_GPIOE |
+ RCC_APB2Periph_GPIOF, ENABLE);
+
+/*-- GPIO Configuration ------------------------------------------------------*/
+ /* SRAM Data lines configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_8 | GPIO_Pin_9 |
+ GPIO_Pin_10 | GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10 |
+ GPIO_Pin_11 | GPIO_Pin_12 | GPIO_Pin_13 | GPIO_Pin_14 |
+ GPIO_Pin_15;
+ GPIO_Init(GPIOE, &GPIO_InitStructure);
+
+ /* SRAM Address lines configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3 |
+ GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_12 | GPIO_Pin_13 |
+ GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_Init(GPIOF, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3 |
+ GPIO_Pin_4 | GPIO_Pin_5;
+ GPIO_Init(GPIOG, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12 | GPIO_Pin_13;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ /* NOE and NWE configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 |GPIO_Pin_5;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+
+ /* NE3 configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_Init(GPIOG, &GPIO_InitStructure);
+
+ /* NBL0, NBL1 configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1;
+ GPIO_Init(GPIOE, &GPIO_InitStructure);
+
+/*-- FSMC Configuration ------------------------------------------------------*/
+ p.FSMC_AddressSetupTime = 0;
+ p.FSMC_AddressHoldTime = 0;
+ p.FSMC_DataSetupTime = 2;
+ p.FSMC_BusTurnAroundDuration = 0;
+ p.FSMC_CLKDivision = 0;
+ p.FSMC_DataLatency = 0;
+ p.FSMC_AccessMode = FSMC_AccessMode_A;
+
+ FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM3;
+ FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
+ FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+ FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+ FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_AsyncWait = FSMC_AsyncWait_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p;
+ FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p;
+
+ FSMC_NORSRAMInit(&FSMC_NORSRAMInitStructure);
+
+ /* Enable FSMC Bank1_SRAM Bank */
+ FSMC_NORSRAMCmd(FSMC_Bank1_NORSRAM3, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : FSMC_SRAM_WriteBuffer
+* Description : Writes a Half-word buffer to the FSMC SRAM memory.
+* Input : - pBuffer : pointer to buffer.
+* - WriteAddr : SRAM memory internal address from which the data
+* will be written.
+* - NumHalfwordToWrite : number of half-words to write.
+*
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_SRAM_WriteBuffer(u16* pBuffer, u32 WriteAddr, u32 NumHalfwordToWrite)
+{
+ for(; NumHalfwordToWrite != 0; NumHalfwordToWrite--) /* while there is data to write */
+ {
+ /* Transfer data to the memory */
+ *(u16 *) (Bank1_SRAM3_ADDR + WriteAddr) = *pBuffer++;
+
+ /* Increment the address*/
+ WriteAddr += 2;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_SRAM_ReadBuffer
+* Description : Reads a block of data from the FSMC SRAM memory.
+* Input : - pBuffer : pointer to the buffer that receives the data read
+* from the SRAM memory.
+* - ReadAddr : SRAM memory internal address to read from.
+* - NumHalfwordToRead : number of half-words to read.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_SRAM_ReadBuffer(u16* pBuffer, u32 ReadAddr, u32 NumHalfwordToRead)
+{
+ for(; NumHalfwordToRead != 0; NumHalfwordToRead--) /* while there is data to read */
+ {
+ /* Read a half-word from the memory */
+ *pBuffer++ = *(vu16*) (Bank1_SRAM3_ADDR + ReadAddr);
+
+ /* Increment the address*/
+ ReadAddr += 2;
+ }
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/SRAM/fsmc_sram.h b/src/stm32lib/examples/FSMC/SRAM/fsmc_sram.h new file mode 100755 index 0000000..f599266 --- /dev/null +++ b/src/stm32lib/examples/FSMC/SRAM/fsmc_sram.h @@ -0,0 +1,33 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : fsmc_sram.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Header for fsmc_sram.c file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __FSMC_SRAM_H
+#define __FSMC_SRAM_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void FSMC_SRAM_Init(void);
+void FSMC_SRAM_WriteBuffer(u16* pBuffer, u32 WriteAddr, u32 NumHalfwordToWrite);
+void FSMC_SRAM_ReadBuffer(u16* pBuffer, u32 ReadAddr, u32 NumHalfwordToRead);
+
+#endif /* __FSMC_SRAM_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/SRAM/main.c b/src/stm32lib/examples/FSMC/SRAM/main.c new file mode 100755 index 0000000..f7c2f0d --- /dev/null +++ b/src/stm32lib/examples/FSMC/SRAM/main.c @@ -0,0 +1,223 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+/* Includes ------------------------------------------------------------------*/
+#include "fsmc_sram.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define BUFFER_SIZE 0x400
+#define WRITE_READ_ADDR 0x8000
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+GPIO_InitTypeDef GPIO_InitStructure;
+ErrorStatus HSEStartUpStatus;
+
+u16 TxBuffer[BUFFER_SIZE];
+u16 RxBuffer[BUFFER_SIZE];
+u32 WriteReadStatus = 0, Index = 0;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+void Fill_Buffer(u16 *pBuffer, u16 BufferLenght, u32 Offset);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* PF.06 and PF.07 config to drive LD1 and LD2 ******************************/
+ /* Enable GPIOF clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOF, ENABLE);
+
+ /* Configure PF.06 and PF.07 as Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOF, &GPIO_InitStructure);
+
+ /* Write/read to/from FSMC SRAM memory *************************************/
+ /* Enable the FSMC Clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_FSMC, ENABLE);
+
+ /* Configure FSMC Bank1 NOR/SRAM3 */
+ FSMC_SRAM_Init();
+
+ /* Write data to FSMC SRAM memory */
+ /* Fill the buffer to send */
+ Fill_Buffer(TxBuffer, BUFFER_SIZE, 0x3212);
+ FSMC_SRAM_WriteBuffer(TxBuffer, WRITE_READ_ADDR, BUFFER_SIZE);
+
+
+ /* Read data from FSMC SRAM memory */
+ FSMC_SRAM_ReadBuffer(RxBuffer, WRITE_READ_ADDR, BUFFER_SIZE);
+
+ /* Read back SRAM memory and check content correctness */
+ for (Index = 0x00; (Index < BUFFER_SIZE) && (WriteReadStatus == 0); Index++)
+ {
+ if (RxBuffer[Index] != TxBuffer[Index])
+ {
+ WriteReadStatus = Index + 1;
+ }
+ }
+
+ if (WriteReadStatus == 0)
+ { /* OK */
+ /* Turn on LD1 */
+ GPIO_SetBits(GPIOF, GPIO_Pin_6);
+ }
+ else
+ { /* KO */
+ /* Turn off LD2 */
+ GPIO_SetBits(GPIOF, GPIO_Pin_7);
+ }
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function name : Fill_Buffer
+* Description : Fill the global buffer
+* Input : - pBuffer: pointer on the Buffer to fill
+* - BufferSize: size of the buffer to fill
+* - Offset: first value to fill on the Buffer
+* Output param : None
+*******************************************************************************/
+void Fill_Buffer(u16 *pBuffer, u16 BufferLenght, u32 Offset)
+{
+ u16 IndexTmp = 0;
+
+ /* Put in global buffer same values */
+ for (IndexTmp = 0; IndexTmp < BufferLenght; IndexTmp++ )
+ {
+ pBuffer[IndexTmp] = IndexTmp + Offset;
+ }
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/SRAM/readme.txt b/src/stm32lib/examples/FSMC/SRAM/readme.txt new file mode 100755 index 0000000..b9aefda --- /dev/null +++ b/src/stm32lib/examples/FSMC/SRAM/readme.txt @@ -0,0 +1,54 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the FSMC SRAM Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a basic example of how to use the FSMC firmware library and
+an associate driver to perform read/write operations on the IS61WV51216BLL SRAM
+memory mounted on STM3210E-EVAL board.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+fsmc_sram.c Driver for SRAM memory
+fsmc_sram.h Header for fsmc_sram.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_fsmc.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/FSMC/SRAM/stm32f10x_conf.h b/src/stm32lib/examples/FSMC/SRAM/stm32f10x_conf.h new file mode 100755 index 0000000..48e488f --- /dev/null +++ b/src/stm32lib/examples/FSMC/SRAM/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+#define _GPIOD
+#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/SRAM/stm32f10x_it.c b/src/stm32lib/examples/FSMC/SRAM/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/FSMC/SRAM/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/SRAM/stm32f10x_it.h b/src/stm32lib/examples/FSMC/SRAM/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/FSMC/SRAM/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/SRAM_DataMemory/main.c b/src/stm32lib/examples/FSMC/SRAM_DataMemory/main.c new file mode 100755 index 0000000..0a5a0d9 --- /dev/null +++ b/src/stm32lib/examples/FSMC/SRAM_DataMemory/main.c @@ -0,0 +1,164 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+u32 Tab[1024], Index;
+vu32 TabAddr, MSPValue = 0;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+
+ for (Index = 0; Index <1024 ; Index++)
+ {
+ Tab[Index] =Index;
+ }
+
+ TabAddr = (u32)Tab; /* should be 0x680000xx */
+
+ /* Get main stack pointer value */
+ MSPValue = __MRS_MSP(); /* should be 0x2000xxxx */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/SRAM_DataMemory/readme.txt b/src/stm32lib/examples/FSMC/SRAM_DataMemory/readme.txt new file mode 100755 index 0000000..2048691 --- /dev/null +++ b/src/stm32lib/examples/FSMC/SRAM_DataMemory/readme.txt @@ -0,0 +1,76 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the FSMC SRAM_DataMemory Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to use the external SRAM mounted on STM3210E-EVAL board as
+program data memory and internal SRAM for Stack.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+stm32f10x_vector.s STM32F10x vector table for RVMDK toolchain.
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files:
+ + RVMDK
+ - in Project->Options->Target window, select 'RAM1'and enter 0x68000000 as
+ start address with size of 0x100000 (IRAM1 must be un-checked)
+ - use the "stm32f10x_vector.s" provided within this example directory
+
+ + EWARM4
+ - use "lnkarm_flash_extsram.xcl" as linker file
+ - uncomment "#define DATA_IN_ExtSRAM " in the "stm32f10x_vector.c" file
+
+ + EWARM5
+ - use "stm32f10x_flash_extsram.icf" as linker file
+ - uncomment "#define DATA_IN_ExtSRAM " in the "stm32f10x_vector.c" file
+
+ + RIDE
+ - In the Application options -> script menu, set "Use Default Script File"
+ to "No" and use "stm32f10x_flash_extsram.ld" as Script File.
+ - uncomment "#define DATA_IN_ExtSRAM " in the "stm32f10x_vector.c" file
+
+ + HiTOP
+ - in project->settings->project->tool settings->linker, use "linkextsram"
+ as linker file. With this linker, the external SRAM is used for both
+ program data and Stack.
+ - in cstart_thum2.asm file, change "DATA_IN_ExtSRAM .equ 0"
+ by "DATA_IN_ExtSRAM .equ 1"
+
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_fsmc.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/FSMC/SRAM_DataMemory/stm32f10x_conf.h b/src/stm32lib/examples/FSMC/SRAM_DataMemory/stm32f10x_conf.h new file mode 100755 index 0000000..48e488f --- /dev/null +++ b/src/stm32lib/examples/FSMC/SRAM_DataMemory/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+#define _GPIOD
+#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/SRAM_DataMemory/stm32f10x_it.c b/src/stm32lib/examples/FSMC/SRAM_DataMemory/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/FSMC/SRAM_DataMemory/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/SRAM_DataMemory/stm32f10x_it.h b/src/stm32lib/examples/FSMC/SRAM_DataMemory/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/FSMC/SRAM_DataMemory/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/FSMC/SRAM_DataMemory/stm32f10x_vector.s b/src/stm32lib/examples/FSMC/SRAM_DataMemory/stm32f10x_vector.s new file mode 100755 index 0000000..5323cfa --- /dev/null +++ b/src/stm32lib/examples/FSMC/SRAM_DataMemory/stm32f10x_vector.s @@ -0,0 +1,329 @@ +;******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+;* File Name : stm32f10x_vector.s
+;* Author : MCD Application Team
+;* Version : V2.0.1
+;* Date : 06/13/2008
+;* Description : STM32F10x vector table for RVMDK toolchain.
+;* This module performs:
+;* - Set the initial SP
+;* - Set the initial PC == Reset_Handler
+;* - Set the vector table entries with the exceptions ISR address
+;* - Configure external SRAM mounted on STM3210E-EVAL board
+;* to be used as data memory (optional, to be enabled by user)
+;* - Branches to __main in the C library (which eventually
+;* calls main()).
+;* After Reset the CortexM3 processor is in Thread mode,
+;* priority is Privileged, and the Stack is set to Main.
+;* <<< Use Configuration Wizard in Context Menu >>>
+;*******************************************************************************
+; 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.
+;*******************************************************************************
+
+; If you need to use external SRAM mounted on STM3210E-EVAL board as data memory,
+; change the following define value to '1' (or choose ENABLE in Configuration Wizard window)
+;// <o> External SRAM Configuration <0=> DISABLE <1=> ENABLE
+DATA_IN_ExtSRAM EQU 1
+
+
+; Amount of memory (in bytes) allocated for Stack
+; Tailor this value to your application needs
+;// <h> Stack Configuration
+;// <o> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
+;// </h>
+Stack_Size EQU 0x00000400
+
+ AREA STACK, NOINIT, READWRITE, ALIGN=3
+Stack_Mem SPACE Stack_Size
+
+;__initial_sp
+; If you need to use external SRAM mounted on STM3210E-EVAL board as data memory
+; and internal SRAM for Stack, uncomment the following line and comment the line above
+__initial_sp EQU 0x20000000 + Stack_Size ; "Use MicroLIB" must be checked in
+ ; the Project->Options->Target window
+
+; Amount of memory (in bytes) allocated for Heap
+; Tailor this value to your application needs
+;// <h> Heap Configuration
+;// <o> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
+;// </h>
+
+Heap_Size EQU 0x00000400
+
+ AREA HEAP, NOINIT, READWRITE, ALIGN=3
+__heap_base
+Heap_Mem SPACE Heap_Size
+__heap_limit
+
+
+ THUMB
+ PRESERVE8
+
+ ; Import exceptions handlers
+ IMPORT NMIException
+ IMPORT HardFaultException
+ IMPORT MemManageException
+ IMPORT BusFaultException
+ IMPORT UsageFaultException
+ IMPORT SVCHandler
+ IMPORT DebugMonitor
+ IMPORT PendSVC
+ IMPORT SysTickHandler
+ IMPORT WWDG_IRQHandler
+ IMPORT PVD_IRQHandler
+ IMPORT TAMPER_IRQHandler
+ IMPORT RTC_IRQHandler
+ IMPORT FLASH_IRQHandler
+ IMPORT RCC_IRQHandler
+ IMPORT EXTI0_IRQHandler
+ IMPORT EXTI1_IRQHandler
+ IMPORT EXTI2_IRQHandler
+ IMPORT EXTI3_IRQHandler
+ IMPORT EXTI4_IRQHandler
+ IMPORT DMA1_Channel1_IRQHandler
+ IMPORT DMA1_Channel2_IRQHandler
+ IMPORT DMA1_Channel3_IRQHandler
+ IMPORT DMA1_Channel4_IRQHandler
+ IMPORT DMA1_Channel5_IRQHandler
+ IMPORT DMA1_Channel6_IRQHandler
+ IMPORT DMA1_Channel7_IRQHandler
+ IMPORT ADC1_2_IRQHandler
+ IMPORT USB_HP_CAN_TX_IRQHandler
+ IMPORT USB_LP_CAN_RX0_IRQHandler
+ IMPORT CAN_RX1_IRQHandler
+ IMPORT CAN_SCE_IRQHandler
+ IMPORT EXTI9_5_IRQHandler
+ IMPORT TIM1_BRK_IRQHandler
+ IMPORT TIM1_UP_IRQHandler
+ IMPORT TIM1_TRG_COM_IRQHandler
+ IMPORT TIM1_CC_IRQHandler
+ IMPORT TIM2_IRQHandler
+ IMPORT TIM3_IRQHandler
+ IMPORT TIM4_IRQHandler
+ IMPORT I2C1_EV_IRQHandler
+ IMPORT I2C1_ER_IRQHandler
+ IMPORT I2C2_EV_IRQHandler
+ IMPORT I2C2_ER_IRQHandler
+ IMPORT SPI1_IRQHandler
+ IMPORT SPI2_IRQHandler
+ IMPORT USART1_IRQHandler
+ IMPORT USART2_IRQHandler
+ IMPORT USART3_IRQHandler
+ IMPORT EXTI15_10_IRQHandler
+ IMPORT RTCAlarm_IRQHandler
+ IMPORT USBWakeUp_IRQHandler
+ IMPORT TIM8_BRK_IRQHandler
+ IMPORT TIM8_UP_IRQHandler
+ IMPORT TIM8_TRG_COM_IRQHandler
+ IMPORT TIM8_CC_IRQHandler
+ IMPORT ADC3_IRQHandler
+ IMPORT FSMC_IRQHandler
+ IMPORT SDIO_IRQHandler
+ IMPORT TIM5_IRQHandler
+ IMPORT SPI3_IRQHandler
+ IMPORT UART4_IRQHandler
+ IMPORT UART5_IRQHandler
+ IMPORT TIM6_IRQHandler
+ IMPORT TIM7_IRQHandler
+ IMPORT DMA2_Channel1_IRQHandler
+ IMPORT DMA2_Channel2_IRQHandler
+ IMPORT DMA2_Channel3_IRQHandler
+ IMPORT DMA2_Channel4_5_IRQHandler
+
+;*******************************************************************************
+; Fill-up the Vector Table entries with the exceptions ISR address
+;*******************************************************************************
+ AREA RESET, DATA, READONLY
+ EXPORT __Vectors
+
+__Vectors DCD __initial_sp ; Top of Stack
+ DCD Reset_Handler
+ DCD NMIException
+ DCD HardFaultException
+ DCD MemManageException
+ DCD BusFaultException
+ DCD UsageFaultException
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD 0 ; Reserved
+ DCD SVCHandler
+ DCD DebugMonitor
+ DCD 0 ; Reserved
+ DCD PendSVC
+ DCD SysTickHandler
+ DCD WWDG_IRQHandler
+ DCD PVD_IRQHandler
+ DCD TAMPER_IRQHandler
+ DCD RTC_IRQHandler
+ DCD FLASH_IRQHandler
+ DCD RCC_IRQHandler
+ DCD EXTI0_IRQHandler
+ DCD EXTI1_IRQHandler
+ DCD EXTI2_IRQHandler
+ DCD EXTI3_IRQHandler
+ DCD EXTI4_IRQHandler
+ DCD DMA1_Channel1_IRQHandler
+ DCD DMA1_Channel2_IRQHandler
+ DCD DMA1_Channel3_IRQHandler
+ DCD DMA1_Channel4_IRQHandler
+ DCD DMA1_Channel5_IRQHandler
+ DCD DMA1_Channel6_IRQHandler
+ DCD DMA1_Channel7_IRQHandler
+ DCD ADC1_2_IRQHandler
+ DCD USB_HP_CAN_TX_IRQHandler
+ DCD USB_LP_CAN_RX0_IRQHandler
+ DCD CAN_RX1_IRQHandler
+ DCD CAN_SCE_IRQHandler
+ DCD EXTI9_5_IRQHandler
+ DCD TIM1_BRK_IRQHandler
+ DCD TIM1_UP_IRQHandler
+ DCD TIM1_TRG_COM_IRQHandler
+ DCD TIM1_CC_IRQHandler
+ DCD TIM2_IRQHandler
+ DCD TIM3_IRQHandler
+ DCD TIM4_IRQHandler
+ DCD I2C1_EV_IRQHandler
+ DCD I2C1_ER_IRQHandler
+ DCD I2C2_EV_IRQHandler
+ DCD I2C2_ER_IRQHandler
+ DCD SPI1_IRQHandler
+ DCD SPI2_IRQHandler
+ DCD USART1_IRQHandler
+ DCD USART2_IRQHandler
+ DCD USART3_IRQHandler
+ DCD EXTI15_10_IRQHandler
+ DCD RTCAlarm_IRQHandler
+ DCD USBWakeUp_IRQHandler
+ DCD TIM8_BRK_IRQHandler
+ DCD TIM8_UP_IRQHandler
+ DCD TIM8_TRG_COM_IRQHandler
+ DCD TIM8_CC_IRQHandler
+ DCD ADC3_IRQHandler
+ DCD FSMC_IRQHandler
+ DCD SDIO_IRQHandler
+ DCD TIM5_IRQHandler
+ DCD SPI3_IRQHandler
+ DCD UART4_IRQHandler
+ DCD UART5_IRQHandler
+ DCD TIM6_IRQHandler
+ DCD TIM7_IRQHandler
+ DCD DMA2_Channel1_IRQHandler
+ DCD DMA2_Channel2_IRQHandler
+ DCD DMA2_Channel3_IRQHandler
+ DCD DMA2_Channel4_5_IRQHandler
+
+ AREA |.text|, CODE, READONLY
+
+; Reset handler routine
+Reset_Handler PROC
+ EXPORT Reset_Handler
+
+ IF DATA_IN_ExtSRAM == 1
+; FSMC Bank1 NOR/SRAM3 is used for the STM3210E-EVAL, if another Bank is
+; required, then adjust the Register Addresses
+
+
+; Enable FSMC clock
+ LDR R0,= 0x00000114
+ LDR R1,= 0x40021014
+ STR R0,[R1]
+
+; Enable GPIOD, GPIOE, GPIOF and GPIOG clocks
+ LDR R0,= 0x000001E0
+ LDR R1,= 0x40021018
+ STR R0,[R1]
+
+; SRAM Data lines, NOE and NWE configuration
+; SRAM Address lines configuration
+; NOE and NWE configuration
+; NE3 configuration
+; NBL0, NBL1 configuration
+
+ LDR R0,= 0x44BB44BB
+ LDR R1,= 0x40011400
+ STR R0,[R1]
+
+ LDR R0,= 0xBBBBBBBB
+ LDR R1,= 0x40011404
+ STR R0,[R1]
+
+ LDR R0,= 0xB44444BB
+ LDR R1,= 0x40011800
+ STR R0,[R1]
+
+ LDR R0,= 0xBBBBBBBB
+ LDR R1,= 0x40011804
+ STR R0,[R1]
+
+ LDR R0,= 0x44BBBBBB
+ LDR R1,= 0x40011C00
+ STR R0,[R1]
+
+ LDR R0,= 0xBBBB4444
+ LDR R1,= 0x40011C04
+ STR R0,[R1]
+
+ LDR R0,= 0x44BBBBBB
+ LDR R1,= 0x40012000
+ STR R0,[R1]
+
+ LDR R0,= 0x44444B44
+ LDR R1,= 0x40012004
+ STR R0,[R1]
+
+; FSMC Configuration
+; Enable FSMC Bank1_SRAM Bank
+
+ LDR R0,= 0x00001011
+ LDR R1,= 0xA0000010
+ STR R0,[R1]
+
+ LDR R0,= 0x00000200
+ LDR R1,= 0xA0000014
+ STR R0,[R1]
+
+
+ ENDIF
+
+
+ IMPORT __main
+ LDR R0, =__main
+ BX R0
+ ENDP
+
+ ALIGN
+
+;*******************************************************************************
+; User Stack and Heap initialization
+;*******************************************************************************
+ IF :DEF:__MICROLIB
+
+ EXPORT __initial_sp
+ EXPORT __heap_base
+ EXPORT __heap_limit
+
+ ELSE
+
+ IMPORT __use_two_region_memory
+ EXPORT __user_initial_stackheap
+
+__user_initial_stackheap
+
+ LDR R0, = Heap_Mem
+ LDR R1, =(Stack_Mem + Stack_Size)
+ LDR R2, = (Heap_Mem + Heap_Size)
+ LDR R3, = Stack_Mem
+ BX LR
+
+ ALIGN
+
+ ENDIF
+
+ END
+
+;******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE*****
diff --git a/src/stm32lib/examples/GPIO/IOToggle/main.c b/src/stm32lib/examples/GPIO/IOToggle/main.c new file mode 100755 index 0000000..e6d321f --- /dev/null +++ b/src/stm32lib/examples/GPIO/IOToggle/main.c @@ -0,0 +1,222 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+GPIO_InitTypeDef GPIO_InitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+void Delay(vu32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration **********************************************/
+ RCC_Configuration();
+
+ /* NVIC Configuration *******************************************************/
+ NVIC_Configuration();
+
+ /* Configure all unused GPIO port pins in Analog Input mode (floating input
+ trigger OFF), this will reduce the power consumption and increase the device
+ immunity against EMI/EMC *************************************************/
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB |
+ RCC_APB2Periph_GPIOC | RCC_APB2Periph_GPIOD |
+ RCC_APB2Periph_GPIOE, ENABLE);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+ GPIO_Init(GPIOE, &GPIO_InitStructure);
+
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB |
+ RCC_APB2Periph_GPIOC | RCC_APB2Periph_GPIOD |
+ RCC_APB2Periph_GPIOE, DISABLE);
+#ifdef USE_STM3210E_EVAL
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOF | RCC_APB2Periph_GPIOG, ENABLE);
+
+ GPIO_Init(GPIOF, &GPIO_InitStructure);
+ GPIO_Init(GPIOG, &GPIO_InitStructure);
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOF | RCC_APB2Periph_GPIOG, DISABLE);
+#endif /* USE_STM3210E_EVAL */
+
+ /* Configure IO connected to LD1, LD2, LD3 and LD4 leds *********************/
+ /* Enable GPIO_LED clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_LED, ENABLE);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ while (1)
+ {
+ /* Turn on LD1 */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_6);
+ /* Insert delay */
+ Delay(0xAFFFF);
+
+ /* Turn on LD2 and LD3 */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_7 | GPIO_Pin_8);
+ /* Turn off LD1 */
+ GPIO_ResetBits(GPIO_LED, GPIO_Pin_6);
+ /* Insert delay */
+ Delay(0xAFFFF);
+
+ /* Turn on LD4 */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_9);
+ /* Turn off LD2 and LD3 */
+ GPIO_ResetBits(GPIO_LED, GPIO_Pin_8 | GPIO_Pin_7);
+ /* Insert delay */
+ Delay(0xAFFFF);
+
+ /* Turn off LD4 */
+ GPIO_ResetBits(GPIO_LED, GPIO_Pin_9);
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for(; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/GPIO/IOToggle/platform_config.h b/src/stm32lib/examples/GPIO/IOToggle/platform_config.h new file mode 100755 index 0000000..0bc5169 --- /dev/null +++ b/src/stm32lib/examples/GPIO/IOToggle/platform_config.h @@ -0,0 +1,44 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/GPIO/IOToggle/readme.txt b/src/stm32lib/examples/GPIO/IOToggle/readme.txt new file mode 100755 index 0000000..e0637b0 --- /dev/null +++ b/src/stm32lib/examples/GPIO/IOToggle/readme.txt @@ -0,0 +1,64 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the GPIO IOToggle Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example describes how to use GPIO BSRR (Port bit set/reset register) and
+BRR (Port bit reset register) for IO toggling.
+These registers allow modifying only one or several GPIO pins in a single atomic
+write access.
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PC.06, PC.07, PC.08
+ and PC.09 pins
+
+ + STM3210E-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PF.06, PF0.7, PF.08
+ and PF.09 pins
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/GPIO/IOToggle/stm32f10x_conf.h b/src/stm32lib/examples/GPIO/IOToggle/stm32f10x_conf.h new file mode 100755 index 0000000..95a94fa --- /dev/null +++ b/src/stm32lib/examples/GPIO/IOToggle/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+#define _GPIOD
+#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz */
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/GPIO/IOToggle/stm32f10x_it.c b/src/stm32lib/examples/GPIO/IOToggle/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/GPIO/IOToggle/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/GPIO/IOToggle/stm32f10x_it.h b/src/stm32lib/examples/GPIO/IOToggle/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/GPIO/IOToggle/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/GPIO/JTAG_Remap/main.c b/src/stm32lib/examples/GPIO/JTAG_Remap/main.c new file mode 100755 index 0000000..27561dc --- /dev/null +++ b/src/stm32lib/examples/GPIO/JTAG_Remap/main.c @@ -0,0 +1,224 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+GPIO_InitTypeDef GPIO_InitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+void Delay(vu32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* Configure the system clocks */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* Configure Key Button GPIO Pin as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_KEY_BUTTON;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIO_KEY_BUTTON, &GPIO_InitStructure);
+
+ /* Test if Key Button GPIO Pin level is low (Key push-button on Eval Board pressed) */
+ if (GPIO_ReadInputDataBit(GPIO_KEY_BUTTON, GPIO_PIN_KEY_BUTTON) == 0x00)
+ { /* Key is pressed */
+
+ /* Disable the Serial Wire Jtag Debug Port SWJ-DP */
+ GPIO_PinRemapConfig(GPIO_Remap_SWJ_Disable, ENABLE);
+
+ /* Configure PA.13 (JTMS/SWDAT), PA.14 (JTCK/SWCLK) and PA.15 (JTDI) as
+ output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure PB.03 (JTDO) and PB.04 (JTRST) as output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3 | GPIO_Pin_4;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ while (1)
+ {
+ /* Toggle JTMS/SWDAT pin */
+ GPIO_WriteBit(GPIOA, GPIO_Pin_13, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIOA, GPIO_Pin_13)));
+ /* Insert delay */
+ Delay(0x5FFFF);
+
+ /* Toggle JTCK/SWCLK pin */
+ GPIO_WriteBit(GPIOA, GPIO_Pin_14, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIOA, GPIO_Pin_14)));
+ /* Insert delay */
+ Delay(0x5FFFF);
+
+ /* Toggle JTDI pin */
+ GPIO_WriteBit(GPIOA, GPIO_Pin_15, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIOA, GPIO_Pin_15)));
+ /* Insert delay */
+ Delay(0x5FFFF);
+
+ /* Toggle JTDO pin */
+ GPIO_WriteBit(GPIOB, GPIO_Pin_3, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIOB, GPIO_Pin_3)));
+ /* Insert delay */
+ Delay(0x5FFFF);
+
+ /* Toggle JTRST pin */
+ GPIO_WriteBit(GPIOB, GPIO_Pin_4, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIOB, GPIO_Pin_4)));
+ /* Insert delay */
+ Delay(0x5FFFF);
+ }
+ }
+ else
+ {
+ while (1)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable GPIOA, GPIOB, RCC_APB2Periph_GPIO_KEY_BUTTON and AFIO clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB |
+ RCC_APB2Periph_GPIO_KEY_BUTTON | RCC_APB2Periph_AFIO, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for(; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/GPIO/JTAG_Remap/platform_config.h b/src/stm32lib/examples/GPIO/JTAG_Remap/platform_config.h new file mode 100755 index 0000000..b10ebac --- /dev/null +++ b/src/stm32lib/examples/GPIO/JTAG_Remap/platform_config.h @@ -0,0 +1,46 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_KEY_BUTTON GPIOB
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOB
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_9
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_KEY_BUTTON GPIOG
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOG
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_8
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/GPIO/JTAG_Remap/readme.txt b/src/stm32lib/examples/GPIO/JTAG_Remap/readme.txt new file mode 100755 index 0000000..2393f16 --- /dev/null +++ b/src/stm32lib/examples/GPIO/JTAG_Remap/readme.txt @@ -0,0 +1,73 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the GPIO JTAG Remap Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a short description of how to use the JTAG IOs as standard
+GPIOs and gives a configuration sequence.
+
+First, the SWJ-DP is disabled. The SWJ-DP pins are configured as output push-pull.
+Five LEDs connected to the PA.13(JTMS/SWDAT), PA.14(JTCK/SWCLK), PA.15(JTDI),
+PB.03(JTDO) and PB.04(JTRST) pins are toggled in an infinite loop.
+
+Note that once the JTAG IOs are disabled, the connection with the host debugger is
+lost and cannot be re-established as long as the JTAG IOs remain disabled.
+To avoid this situation, a specified pin is connected to a push-button that is used
+to disable or not the JTAG IOs:
+ 1. push-button pressed at reset: JTAG IOs disabled
+ 2. push-button not pressed at reset: JTAG IOs unchanged
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Connect five leds to pins PA.13, PA.14, PA.15, PB.03 and PB.04.
+ - Use the Key push-button connected to pin PB.09 (EXTI Line9).
+
+ + STM3210E-EVAL
+ - Connect five leds to pins PA.13, PA.14, PA.15, PB.03 and PB.04.
+ - Use the Key push-button connectedto pin PG.08 (EXTI Line8).
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/GPIO/JTAG_Remap/stm32f10x_conf.h b/src/stm32lib/examples/GPIO/JTAG_Remap/stm32f10x_conf.h new file mode 100755 index 0000000..a18e5fb --- /dev/null +++ b/src/stm32lib/examples/GPIO/JTAG_Remap/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/GPIO/JTAG_Remap/stm32f10x_it.c b/src/stm32lib/examples/GPIO/JTAG_Remap/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/GPIO/JTAG_Remap/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/GPIO/JTAG_Remap/stm32f10x_it.h b/src/stm32lib/examples/GPIO/JTAG_Remap/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/GPIO/JTAG_Remap/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/10bitAddress/main.c b/src/stm32lib/examples/I2C/10bitAddress/main.c new file mode 100755 index 0000000..db28680 --- /dev/null +++ b/src/stm32lib/examples/I2C/10bitAddress/main.c @@ -0,0 +1,281 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define I2C1_SLAVE_ADDRESS7 0x30
+#define I2C2_SLAVE_ADDRESS7 0x30
+#define I2C2_SLAVE_ADDRESS10 0x0330
+#define BufferSize 4
+#define ClockSpeed 300000
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+I2C_InitTypeDef I2C_InitStructure;
+u8 I2C1_Buffer_Tx[BufferSize] = {1,2,3,4};
+u8 I2C2_Buffer_Rx[BufferSize];
+u8 TxIdx = 0, RxIdx = 0;
+volatile TestStatus TransferStatus = FAILED;
+u8 HeaderAddressWrite = (((I2C2_SLAVE_ADDRESS10 & 0xFF00) >>7) | 0xF0) ;
+ErrorStatus HSEStartUpStatus;
+
+/* Private functions ---------------------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength);
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* Enable I2C1 and I2C2 ----------------------------------------------------*/
+ I2C_Cmd(I2C1, ENABLE);
+ I2C_Cmd(I2C2, ENABLE);
+
+ /* I2C1 configuration ------------------------------------------------------*/
+ I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
+ I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2;
+ I2C_InitStructure.I2C_OwnAddress1 = I2C1_SLAVE_ADDRESS7;
+ I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
+ I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
+ I2C_InitStructure.I2C_ClockSpeed = ClockSpeed;
+ I2C_Init(I2C1, &I2C_InitStructure);
+
+ /* I2C2 configuration ------------------------------------------------------*/
+ I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_10bit;
+ I2C_InitStructure.I2C_OwnAddress1 = I2C2_SLAVE_ADDRESS10;
+ I2C_Init(I2C2, &I2C_InitStructure);
+
+ /*----- Transmission Phase -----*/
+ /* Send I2C1 START condition */
+ I2C_GenerateSTART(I2C1, ENABLE);
+ /* Test on I2C1 EV5 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_MODE_SELECT));
+ /* Send Header to I2C2 for write */
+ I2C_SendData(I2C1, HeaderAddressWrite);
+ /* Test on I2C1 EV9 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_MODE_ADDRESS10));
+ /* Send I2C2 slave Address for write */
+ I2C_Send7bitAddress(I2C1, I2C2_SLAVE_ADDRESS7, I2C_Direction_Transmitter);
+ /* Test on I2C2 EV1 and clear it */
+ while(!I2C_CheckEvent(I2C2, I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED));
+ /* Test on I2C1 EV6 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED));
+
+ /* Send data */
+ while (RxIdx < BufferSize)
+ {
+ /* Send I2C1 data */
+ I2C_SendData(I2C1, I2C1_Buffer_Tx[TxIdx++]);
+ /* Test on I2C2 EV2 and clear it */
+ while(!I2C_CheckEvent(I2C2, I2C_EVENT_SLAVE_BYTE_RECEIVED));
+ /* Store received data on I2C2 */
+ I2C2_Buffer_Rx[RxIdx++] = I2C_ReceiveData(I2C2);
+ /* Test on I2C1 EV8 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_TRANSMITTED));
+ }
+ /* Send I2C1 STOP Condition */
+ I2C_GenerateSTOP(I2C1, ENABLE);
+ /* Test on I2C2 EV4 and clear it */
+ while(!I2C_CheckEvent(I2C2, I2C_EVENT_SLAVE_STOP_DETECTED));
+ /* Clear I2C2 STOPF flag */
+ I2C_ClearFlag(I2C2, I2C_FLAG_STOPF);
+
+ /* Check the corectness of written data */
+ TransferStatus = Buffercmp(I2C1_Buffer_Tx, I2C2_Buffer_Rx, BufferSize);
+ /* TransferStatus = PASSED, if the transmitted and received data
+ are equal */
+ /* TransferStatus = FAILED, if the transmitted and received data
+ are different */
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* GPIOB Periph clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
+ /* I2C1 and I2C2 Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1 | RCC_APB1Periph_I2C2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure I2C1 pins: SCL and SDA ----------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* Configure I2C2 pins: SCL and SDA ----------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/10bitAddress/readme.txt b/src/stm32lib/examples/I2C/10bitAddress/readme.txt new file mode 100755 index 0000000..a14775f --- /dev/null +++ b/src/stm32lib/examples/I2C/10bitAddress/readme.txt @@ -0,0 +1,69 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the I2C 10bit addressing mode example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to transfer a data buffer from I2C1 to
+I2C2 in 10-bit addressing mode.
+
+After enabling the two I2C peripherals, the transfer in 10-bit addressing mode
+starts after the I2C1 start condition is generated. Each time an event occurs on
+the master or the slave, it is managed on I2C1 or I2C2, respectively.
+In this application, Tx_Buffer is transmitted from the master I2C1 to the slave
+I2C2 and stored into Rx_Buffer. The transmitted and received buffers are compared
+to check that all data have been correctly transferred.
+
+The communication clock speed is set to 300KHz.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+ - Connect I2C1 SCL pin (PB.06) to I2C2 SCL pin (PB.10)
+ - Connect I2C1 SDA pin (PB.07) to I2C2 SDA pin (PB.11)
+ - Check that a pull-up resistor is connected on one I2C SDA pin
+ - Check that a pull-up resistor is connected on one I2C SCL pin
+
+Note: The pull-up resitors are already implemented on the STM3210B-EVAL and
+ STM3210E-EVAL evaluation boards.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_i2c.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_gpio.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/I2C/10bitAddress/stm32f10x_conf.h b/src/stm32lib/examples/I2C/10bitAddress/stm32f10x_conf.h new file mode 100755 index 0000000..2281b25 --- /dev/null +++ b/src/stm32lib/examples/I2C/10bitAddress/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+#define _I2C
+#define _I2C1
+#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/10bitAddress/stm32f10x_it.c b/src/stm32lib/examples/I2C/10bitAddress/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/I2C/10bitAddress/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/10bitAddress/stm32f10x_it.h b/src/stm32lib/examples/I2C/10bitAddress/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/I2C/10bitAddress/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/DualAddress/main.c b/src/stm32lib/examples/I2C/DualAddress/main.c new file mode 100755 index 0000000..2cba3fc --- /dev/null +++ b/src/stm32lib/examples/I2C/DualAddress/main.c @@ -0,0 +1,321 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum { FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define I2C1_SLAVE_ADDRESS7 0x30
+#define I2C2_SLAVE1_ADDRESS7 0x30
+#define I2C2_SLAVE2_ADDRESS7 0x22
+#define BufferSize 4
+#define ClockSpeed 200000
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+I2C_InitTypeDef I2C_InitStructure;
+u8 I2C1_Buffer1_Tx[BufferSize] = {1,2,3,4}, I2C1_Buffer2_Tx[BufferSize] = {5,6,7,8};
+u8 I2C2_Buffer1_Rx[BufferSize], I2C2_Buffer2_Rx[BufferSize];
+u8 Tx_Idx = 0, Rx_Idx = 0;
+volatile TestStatus TransferStatus1 = FAILED, TransferStatus2 = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private functions ---------------------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength);
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* Enable I2C1 and I2C2 ----------------------------------------------------*/
+ I2C_Cmd(I2C1, ENABLE);
+ I2C_Cmd(I2C2, ENABLE);
+
+ /* I2C1 configuration ------------------------------------------------------*/
+ I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
+ I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2;
+ I2C_InitStructure.I2C_OwnAddress1 = I2C1_SLAVE_ADDRESS7;
+ I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
+ I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
+ I2C_InitStructure.I2C_ClockSpeed = ClockSpeed;
+ I2C_Init(I2C1, &I2C_InitStructure);
+ /* I2C2 configuration ------------------------------------------------------*/
+ I2C_InitStructure.I2C_OwnAddress1 = I2C2_SLAVE1_ADDRESS7;
+ I2C_Init(I2C2, &I2C_InitStructure);
+
+ /* I2C2 second address configuration */
+ I2C_OwnAddress2Config(I2C2, I2C2_SLAVE2_ADDRESS7);
+ /* Enable I2C2 Dual address */
+ I2C_DualAddressCmd(I2C2, ENABLE);
+
+ /*----- First transmission Phase -----*/
+ /* Send I2C1 START condition */
+ I2C_GenerateSTART(I2C1, ENABLE);
+ /* Test on I2C1 EV5 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_MODE_SELECT));
+ /* Send I2C2 slave Address for write */
+ I2C_Send7bitAddress(I2C1, I2C2_SLAVE1_ADDRESS7, I2C_Direction_Transmitter);
+ /* Test on I2C2 EV1 and clear it */
+ while(!I2C_CheckEvent(I2C2, I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED));
+ /* Test on I2C1 EV6 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED));
+
+ /* Send data */
+ while (Rx_Idx < BufferSize)
+ {
+ /* Send I2C1 data */
+ I2C_SendData(I2C1, I2C1_Buffer1_Tx[Tx_Idx++]);
+ /* Test on I2C2 EV2 and clear it */
+ while(!I2C_CheckEvent(I2C2, I2C_EVENT_SLAVE_BYTE_RECEIVED));
+ /* Store received data on I2C2 */
+ I2C2_Buffer1_Rx[Rx_Idx++] = I2C_ReceiveData(I2C2);
+ /* Test on I2C1 EV8 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_TRANSMITTED));
+ }
+
+ /* Send I2C1 STOP Condition */
+ I2C_GenerateSTOP(I2C1, ENABLE);
+ /* Test on I2C2 EV4 and clear it */
+ while(!I2C_CheckEvent(I2C2, I2C_EVENT_SLAVE_STOP_DETECTED));
+ /* Clear I2C2 STOPF flag */
+ I2C_ClearFlag(I2C2, I2C_FLAG_STOPF);
+
+ /* Check the corectness of written data */
+ TransferStatus1 = Buffercmp(I2C1_Buffer1_Tx, I2C2_Buffer1_Rx, BufferSize);
+ /* TransferStatus1 = PASSED, if the transmitted and received data
+ are equal */
+ /* TransferStatus1 = FAILED, if the transmitted and received data
+ are different */
+
+ /*----- Second transmission Phase -----*/
+ /* Reset counters and reception buffer */
+ Tx_Idx = Rx_Idx = 0;
+ /* Send I2C1 START condition */
+ I2C_GenerateSTART(I2C1, ENABLE);
+ /* Test on I2C1 EV5 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_MODE_SELECT));
+ /* Send I2C2 slave Address for write */
+ I2C_Send7bitAddress(I2C1, I2C2_SLAVE2_ADDRESS7, I2C_Direction_Transmitter);
+ /* Test on I2C2 EV1 and clear it */
+ while(!I2C_CheckEvent(I2C2, I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED));
+ /* Test on I2C1 EV6 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED));
+
+ /* Send data */
+ while (Rx_Idx < BufferSize)
+ {
+ /* Send I2C1 data */
+ I2C_SendData(I2C1, I2C1_Buffer2_Tx[Tx_Idx++]);
+ /* Test on I2C2 EV2 and clear it */
+ while(!I2C_CheckEvent(I2C2, I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF));
+ /* Store received data on I2C2 */
+ I2C2_Buffer2_Rx[Rx_Idx++] = I2C_ReceiveData(I2C2);
+ /* Test on I2C1 EV8 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_TRANSMITTED));
+ }
+
+ /* Send I2C1 STOP Condition */
+ I2C_GenerateSTOP(I2C1, ENABLE);
+ /* Test on I2C2 EV4 and clear it */
+ while(!I2C_CheckEvent(I2C2, I2C_EVENT_SLAVE_STOP_DETECTED));
+ /* Clear I2C2 STOPF flag */
+ I2C_ClearFlag(I2C2, I2C_FLAG_STOPF);
+
+ /* Check the corectness of written data */
+ TransferStatus2 = Buffercmp(I2C1_Buffer2_Tx, I2C2_Buffer2_Rx, BufferSize);
+ /* TransferStatus2 = PASSED, if the transmitted and received data
+ are equal */
+ /* TransferStatus2 = FAILED, if the transmitted and received data
+ are different */
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* GPIOB Periph clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
+ /* I2C1 and I2C2 Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1 | RCC_APB1Periph_I2C2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure I2C1 pins: SCL and SDA ----------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* Configure I2C2 pins: SCL and SDA ----------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/DualAddress/readme.txt b/src/stm32lib/examples/I2C/DualAddress/readme.txt new file mode 100755 index 0000000..d192246 --- /dev/null +++ b/src/stm32lib/examples/I2C/DualAddress/readme.txt @@ -0,0 +1,75 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the I2C dual addressng mode example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to transfer two data buffer from I2C1
+to I2C2 using its both addresses in the same application.
+
+The example consist in two parts:
+1. First step, the I2C1 master transmitter sends the Tx_Buffer1 data buffer to the
+ slave I2C2 which saves the received data in Rx_Buffer1. I2C2 is addressed in
+ this case by its first slave address I2C2_SLAVE1_ADDRESS7 programmed in the
+ I2C2 OAR1 register.
+ The transmitted and received buffers are compared to check that all data
+ have been correctly transferred.
+2. Second step, the I2C2 is now addressed by its second slave address
+ I2C2_SLAVE2_ADDRESS7 programmed in the I2C2 OAR2 register. The Tx_Buffer2
+ contents are transmitted by the master I2C1 to the slave I2C2 which stores
+ them into Rx_Buffer2.
+ A second comparison takes place between the transmitted and received buffers.
+
+The communication clock speed is set to 200KHz.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+ - Connect I2C1 SCL pin (PB.06) to I2C2 SCL pin (PB.10)
+ - Connect I2C1 SDA pin (PB.07) to I2C2 SDA pin (PB.11)
+ - Check that a pull-up resistor is connected on one I2C SDA pin
+ - Check that a pull-up resistor is connected on one I2C SCL pin
+
+Note: The pull-up resitors are already implemented on the STM3210B-EVAL and
+ STM3210E-EVAL evaluation boards.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_i2c.c
+ + stm32f10x_rcc.c
+ + stm32f10x_gpio.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/I2C/DualAddress/stm32f10x_conf.h b/src/stm32lib/examples/I2C/DualAddress/stm32f10x_conf.h new file mode 100755 index 0000000..2281b25 --- /dev/null +++ b/src/stm32lib/examples/I2C/DualAddress/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+#define _I2C
+#define _I2C1
+#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/DualAddress/stm32f10x_it.c b/src/stm32lib/examples/I2C/DualAddress/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/I2C/DualAddress/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/DualAddress/stm32f10x_it.h b/src/stm32lib/examples/I2C/DualAddress/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/I2C/DualAddress/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/Interrupt/main.c b/src/stm32lib/examples/I2C/Interrupt/main.c new file mode 100755 index 0000000..2b8f2d7 --- /dev/null +++ b/src/stm32lib/examples/I2C/Interrupt/main.c @@ -0,0 +1,271 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define I2C1_SLAVE_ADDRESS7 0x30
+#define I2C2_SLAVE_ADDRESS7 0x30
+#define BufferSize 4
+#define ClockSpeed 200000
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+I2C_InitTypeDef I2C_InitStructure;
+u8 I2C1_Buffer_Tx[BufferSize] = {1,2,3,4};
+u8 I2C2_Buffer_Rx[BufferSize];
+vu8 Tx_Idx = 0, Rx_Idx = 0, PEC_Value = 0;
+volatile TestStatus TransferStatus = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private functions ---------------------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength);
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* Enable I2C1 and I2C2 ----------------------------------------------------*/
+ I2C_Cmd(I2C1, ENABLE);
+ I2C_Cmd(I2C2, ENABLE);
+
+ /* Enable I2C1 and I2C2 event and buffer interrupt */
+ I2C_ITConfig(I2C1, I2C_IT_EVT | I2C_IT_BUF, ENABLE);
+ I2C_ITConfig(I2C2, I2C_IT_EVT | I2C_IT_BUF, ENABLE);
+
+ /* I2C1 configuration ------------------------------------------------------*/
+ I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
+ I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2;
+ I2C_InitStructure.I2C_OwnAddress1 = I2C1_SLAVE_ADDRESS7;
+ I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
+ I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
+ I2C_InitStructure.I2C_ClockSpeed = ClockSpeed;
+ I2C_Init(I2C1, &I2C_InitStructure);
+ /* I2C2 configuration ------------------------------------------------------*/
+ I2C_InitStructure.I2C_OwnAddress1 = I2C2_SLAVE_ADDRESS7;
+ I2C_Init(I2C2, &I2C_InitStructure);
+
+ /*----- Transmission Phase -----*/
+ /* Send I2C1 START condition */
+ I2C_GenerateSTART(I2C1, ENABLE);
+
+ /* Send data */
+ while(Rx_Idx < (BufferSize+1))
+ {
+ }
+
+ /* Check the corectness of written data */
+ TransferStatus = Buffercmp(I2C1_Buffer_Tx, I2C2_Buffer_Rx, BufferSize);
+ /* TransferStatus = PASSED, if the transmitted and received data
+ are equal */
+ /* TransferStatus = FAILED, if the transmitted and received data
+ are different */
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* Enable I2C1 and I2C2 clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1 | RCC_APB1Periph_I2C2, ENABLE);
+ /* Enable GPIOB clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure I2C1 pins: SCL and SDA ----------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* Configure I2C2 pins: SCL and SDA ----------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures NVIC and Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* 1 bit for pre-emption priority, 3 bits for subpriority */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
+
+ /* Configure and enable I2C1 interrupt -------------------------------------*/
+ NVIC_InitStructure.NVIC_IRQChannel = I2C1_EV_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Configure and enable I2C2 interrupt -------------------------------------*/
+ NVIC_InitStructure.NVIC_IRQChannel = I2C2_EV_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/Interrupt/readme.txt b/src/stm32lib/examples/I2C/Interrupt/readme.txt new file mode 100755 index 0000000..2325532 --- /dev/null +++ b/src/stm32lib/examples/I2C/Interrupt/readme.txt @@ -0,0 +1,74 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the I2C interrupt mode example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to transfer a data buffer from I2C1 to
+I2C2 using interrupts.
+
+After enabling the two I2C peripherals and both event and buffer interrupts,
+the transfer in 7-bit addressing mode starts after I2C1 start condition generation.
+
+Each time an event occurs on the master or the slave, it is managed in the I2C1 or
+I2C2 interrupt routine, respectively. In this application, Tx_Buffer is transmitted
+from the master I2C1 to the slave I2C2 and stored into Rx_Buffer.
+
+At the end of the transfer, the PEC is transmitted from master to slave and it is
+stored in the PEC_Value variable by I2C2 after reception.
+The transmitted and received buffers are compared to check that all data have been
+correctly transferred.
+
+The communication clock speed is set to 200KHz.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+ - Connect I2C1 SCL pin (PB.06) to I2C2 SCL pin (PB.10)
+ - Connect I2C1 SDA pin (PB.07) to I2C2 SDA pin (PB.11)
+ - Check that a pull-up resistor is connected on one I2C SDA pin
+ - Check that a pull-up resistor is connected on one I2C SCL pin
+
+Note: The pull-up resitors are already implemented on the STM3210B-EVAL and
+ STM3210E-EVAL evaluation boards.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_i2c.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_gpio.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/I2C/Interrupt/stm32f10x_conf.h b/src/stm32lib/examples/I2C/Interrupt/stm32f10x_conf.h new file mode 100755 index 0000000..2281b25 --- /dev/null +++ b/src/stm32lib/examples/I2C/Interrupt/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+#define _I2C
+#define _I2C1
+#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/Interrupt/stm32f10x_it.c b/src/stm32lib/examples/I2C/Interrupt/stm32f10x_it.c new file mode 100755 index 0000000..0757a19 --- /dev/null +++ b/src/stm32lib/examples/I2C/Interrupt/stm32f10x_it.c @@ -0,0 +1,888 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define BufferSize 4
+#define I2C2_SLAVE_ADDRESS7 0x30
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+extern vu8 Tx_Idx, Rx_Idx, PEC_Value, DataToTransfer;
+extern u8 I2C1_Buffer_Tx[], I2C2_Buffer_Rx[];
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+ switch (I2C_GetLastEvent(I2C1))
+ {
+ /* Test on I2C1 EV5 and clear it */
+ case I2C_EVENT_MASTER_MODE_SELECT:
+ /* Send I2C2 slave Address for write */
+ I2C_Send7bitAddress(I2C1, I2C2_SLAVE_ADDRESS7, I2C_Direction_Transmitter);
+ break;
+
+ /* Test on I2C1 EV6 and first EV8 and clear them */
+ case I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED:
+ /* I2C1 and I2C2 PEC Transmission Enable */
+ I2C_CalculatePEC(I2C1, ENABLE);
+ I2C_CalculatePEC(I2C2, ENABLE);
+ /* Send the first data */
+ I2C_SendData(I2C1, I2C1_Buffer_Tx[Tx_Idx++]); /* EV8 just after EV6 */
+ break;
+
+ /* Test on I2C1 EV8 and clear it */
+ case I2C_EVENT_MASTER_BYTE_TRANSMITTED:
+ if(Tx_Idx < BufferSize)
+ {
+ /* Transmit buffer data */
+ I2C_SendData(I2C1, I2C1_Buffer_Tx[Tx_Idx++]);
+ }
+ else
+ {
+ /* Disable I2C1 interrupts */
+ I2C_ITConfig(I2C1, I2C_IT_EVT | I2C_IT_BUF, DISABLE);
+
+ /* Enable Transfer PEC next for I2C1 and I2C2 */
+ I2C_TransmitPEC(I2C2, ENABLE);
+ I2C_TransmitPEC(I2C1, ENABLE);
+ }
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+ switch (I2C_GetLastEvent(I2C2))
+ {
+ /* Test on I2C2 EV1 and clear it */
+ case I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED:
+ break;
+
+ /* Test on I2C2 EV2 and clear it */
+ case I2C_EVENT_SLAVE_BYTE_RECEIVED:
+ if (Rx_Idx < BufferSize)
+ {
+ /* Store received data buffer */
+ I2C2_Buffer_Rx[Rx_Idx++] = I2C_ReceiveData(I2C2);
+ }
+ else
+ {
+ /* Store received PEC value */
+ PEC_Value = I2C_ReceiveData(I2C2);
+ Rx_Idx++;
+ /* Send I2C1 STOP Condition */
+ I2C_GenerateSTOP(I2C1, ENABLE);
+ }
+ break;
+
+ /* Test on I2C2 EV4 and clear it */
+ case I2C_EVENT_SLAVE_STOP_DETECTED:
+ /* Clear STOPF flag */
+ I2C_ClearFlag(I2C2, I2C_FLAG_STOPF);
+ /* Disable I2C2 interrupts */
+ I2C_ITConfig(I2C2, I2C_IT_EVT | I2C_IT_BUF, DISABLE);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/Interrupt/stm32f10x_it.h b/src/stm32lib/examples/I2C/Interrupt/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/I2C/Interrupt/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/M24C08_EEPROM/i2c_ee.c b/src/stm32lib/examples/I2C/M24C08_EEPROM/i2c_ee.c new file mode 100755 index 0000000..f95858a --- /dev/null +++ b/src/stm32lib/examples/I2C/M24C08_EEPROM/i2c_ee.c @@ -0,0 +1,385 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : i2c_ee.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides a set of functions needed to manage the
+* communication between I2C peripheral and I2C M24C08 EEPROM.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "i2c_ee.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define I2C_Speed 400000
+#define I2C1_SLAVE_ADDRESS7 0xA0
+#define I2C_PageSize 16
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+u16 EEPROM_ADDRESS;
+
+/* Private function prototypes -----------------------------------------------*/
+void GPIO_Configuration(void);
+void I2C_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the used I/O ports pin
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure I2C1 pins: SCL and SDA */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : I2C_Configuration
+* Description : I2C Configuration
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_Configuration(void)
+{
+ I2C_InitTypeDef I2C_InitStructure;
+
+ /* I2C configuration */
+ I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
+ I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2;
+ I2C_InitStructure.I2C_OwnAddress1 = I2C1_SLAVE_ADDRESS7;
+ I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
+ I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
+ I2C_InitStructure.I2C_ClockSpeed = I2C_Speed;
+
+ /* I2C Peripheral Enable */
+ I2C_Cmd(I2C1, ENABLE);
+ /* Apply I2C configuration after enabling it */
+ I2C_Init(I2C1, &I2C_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : I2C_EE_Init
+* Description : Initializes peripherals used by the I2C EEPROM driver.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_EE_Init()
+{
+ /* GPIO configuration */
+ GPIO_Configuration();
+
+ /* I2C configuration */
+ I2C_Configuration();
+
+ /* depending on the EEPROM Address selected in the i2c_ee.h file */
+#ifdef EEPROM_Block0_ADDRESS
+ /* Select the EEPROM Block0 to write on */
+ EEPROM_ADDRESS = EEPROM_Block0_ADDRESS;
+#endif
+#ifdef EEPROM_Block1_ADDRESS
+ /* Select the EEPROM Block1 to write on */
+ EEPROM_ADDRESS = EEPROM_Block1_ADDRESS;
+#endif
+#ifdef EEPROM_Block2_ADDRESS
+ /* Select the EEPROM Block2 to write on */
+ EEPROM_ADDRESS = EEPROM_Block2_ADDRESS;
+#endif
+#ifdef EEPROM_Block3_ADDRESS
+ /* Select the EEPROM Block3 to write on */
+ EEPROM_ADDRESS = EEPROM_Block3_ADDRESS;
+#endif
+}
+
+/*******************************************************************************
+* Function Name : I2C_EE_BufferWrite
+* Description : Writes buffer of data to the I2C EEPROM.
+* Input : - pBuffer : pointer to the buffer containing the data to be
+* written to the EEPROM.
+* - WriteAddr : EEPROM's internal address to write to.
+* - NumByteToWrite : number of bytes to write to the EEPROM.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_EE_BufferWrite(u8* pBuffer, u8 WriteAddr, u16 NumByteToWrite)
+{
+ u8 NumOfPage = 0, NumOfSingle = 0, Addr = 0, count = 0;
+
+ Addr = WriteAddr % I2C_PageSize;
+ count = I2C_PageSize - Addr;
+ NumOfPage = NumByteToWrite / I2C_PageSize;
+ NumOfSingle = NumByteToWrite % I2C_PageSize;
+
+ /* If WriteAddr is I2C_PageSize aligned */
+ if(Addr == 0)
+ {
+ /* If NumByteToWrite < I2C_PageSize */
+ if(NumOfPage == 0)
+ {
+ I2C_EE_PageWrite(pBuffer, WriteAddr, NumOfSingle);
+ I2C_EE_WaitEepromStandbyState();
+ }
+ /* If NumByteToWrite > I2C_PageSize */
+ else
+ {
+ while(NumOfPage--)
+ {
+ I2C_EE_PageWrite(pBuffer, WriteAddr, I2C_PageSize);
+ I2C_EE_WaitEepromStandbyState();
+ WriteAddr += I2C_PageSize;
+ pBuffer += I2C_PageSize;
+ }
+
+ if(NumOfSingle!=0)
+ {
+ I2C_EE_PageWrite(pBuffer, WriteAddr, NumOfSingle);
+ I2C_EE_WaitEepromStandbyState();
+ }
+ }
+ }
+ /* If WriteAddr is not I2C_PageSize aligned */
+ else
+ {
+ /* If NumByteToWrite < I2C_PageSize */
+ if(NumOfPage== 0)
+ {
+ I2C_EE_PageWrite(pBuffer, WriteAddr, NumOfSingle);
+ I2C_EE_WaitEepromStandbyState();
+ }
+ /* If NumByteToWrite > I2C_PageSize */
+ else
+ {
+ NumByteToWrite -= count;
+ NumOfPage = NumByteToWrite / I2C_PageSize;
+ NumOfSingle = NumByteToWrite % I2C_PageSize;
+
+ if(count != 0)
+ {
+ I2C_EE_PageWrite(pBuffer, WriteAddr, count);
+ I2C_EE_WaitEepromStandbyState();
+ WriteAddr += count;
+ pBuffer += count;
+ }
+
+ while(NumOfPage--)
+ {
+ I2C_EE_PageWrite(pBuffer, WriteAddr, I2C_PageSize);
+ I2C_EE_WaitEepromStandbyState();
+ WriteAddr += I2C_PageSize;
+ pBuffer += I2C_PageSize;
+ }
+ if(NumOfSingle != 0)
+ {
+ I2C_EE_PageWrite(pBuffer, WriteAddr, NumOfSingle);
+ I2C_EE_WaitEepromStandbyState();
+ }
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_EE_ByteWrite
+* Description : Writes one byte to the I2C EEPROM.
+* Input : - pBuffer : pointer to the buffer containing the data to be
+* written to the EEPROM.
+* - WriteAddr : EEPROM's internal address to write to.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_EE_ByteWrite(u8* pBuffer, u8 WriteAddr)
+{
+ /* Send STRAT condition */
+ I2C_GenerateSTART(I2C1, ENABLE);
+
+ /* Test on EV5 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_MODE_SELECT));
+
+ /* Send EEPROM address for write */
+ I2C_Send7bitAddress(I2C1, EEPROM_ADDRESS, I2C_Direction_Transmitter);
+
+ /* Test on EV6 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED));
+
+ /* Send the EEPROM's internal address to write to */
+ I2C_SendData(I2C1, WriteAddr);
+
+ /* Test on EV8 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_TRANSMITTED));
+
+ /* Send the byte to be written */
+ I2C_SendData(I2C1, *pBuffer);
+
+ /* Test on EV8 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_TRANSMITTED));
+
+ /* Send STOP condition */
+ I2C_GenerateSTOP(I2C1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : I2C_EE_PageWrite
+* Description : Writes more than one byte to the EEPROM with a single WRITE
+* cycle. The number of byte can't exceed the EEPROM page size.
+* Input : - pBuffer : pointer to the buffer containing the data to be
+* written to the EEPROM.
+* - WriteAddr : EEPROM's internal address to write to.
+* - NumByteToWrite : number of bytes to write to the EEPROM.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_EE_PageWrite(u8* pBuffer, u8 WriteAddr, u8 NumByteToWrite)
+{
+ /* Send START condition */
+ I2C_GenerateSTART(I2C1, ENABLE);
+
+ /* Test on EV5 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_MODE_SELECT));
+
+ /* Send EEPROM address for write */
+ I2C_Send7bitAddress(I2C1, EEPROM_ADDRESS, I2C_Direction_Transmitter);
+
+ /* Test on EV6 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED));
+
+ /* Send the EEPROM's internal address to write to */
+ I2C_SendData(I2C1, WriteAddr);
+
+ /* Test on EV8 and clear it */
+ while(! I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_TRANSMITTED));
+
+ /* While there is data to be written */
+ while(NumByteToWrite--)
+ {
+ /* Send the current byte */
+ I2C_SendData(I2C1, *pBuffer);
+
+ /* Point to the next byte to be written */
+ pBuffer++;
+
+ /* Test on EV8 and clear it */
+ while (!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_TRANSMITTED));
+ }
+
+ /* Send STOP condition */
+ I2C_GenerateSTOP(I2C1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : I2C_EE_BufferRead
+* Description : Reads a block of data from the EEPROM.
+* Input : - pBuffer : pointer to the buffer that receives the data read
+* from the EEPROM.
+* - ReadAddr : EEPROM's internal address to read from.
+* - NumByteToRead : number of bytes to read from the EEPROM.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_EE_BufferRead(u8* pBuffer, u8 ReadAddr, u16 NumByteToRead)
+{
+ /* Send START condition */
+ I2C_GenerateSTART(I2C1, ENABLE);
+
+ /* Test on EV5 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_MODE_SELECT));
+
+ /* Send EEPROM address for write */
+ I2C_Send7bitAddress(I2C1, EEPROM_ADDRESS, I2C_Direction_Transmitter);
+
+ /* Test on EV6 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED));
+
+ /* Clear EV6 by setting again the PE bit */
+ I2C_Cmd(I2C1, ENABLE);
+
+ /* Send the EEPROM's internal address to write to */
+ I2C_SendData(I2C1, ReadAddr);
+
+ /* Test on EV8 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_TRANSMITTED));
+
+ /* Send STRAT condition a second time */
+ I2C_GenerateSTART(I2C1, ENABLE);
+
+ /* Test on EV5 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_MODE_SELECT));
+
+ /* Send EEPROM address for read */
+ I2C_Send7bitAddress(I2C1, EEPROM_ADDRESS, I2C_Direction_Receiver);
+
+ /* Test on EV6 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED));
+
+ /* While there is data to be read */
+ while(NumByteToRead)
+ {
+ if(NumByteToRead == 1)
+ {
+ /* Disable Acknowledgement */
+ I2C_AcknowledgeConfig(I2C1, DISABLE);
+
+ /* Send STOP Condition */
+ I2C_GenerateSTOP(I2C1, ENABLE);
+ }
+
+ /* Test on EV7 and clear it */
+ if(I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_RECEIVED))
+ {
+ /* Read a byte from the EEPROM */
+ *pBuffer = I2C_ReceiveData(I2C1);
+
+ /* Point to the next location where the byte read will be saved */
+ pBuffer++;
+
+ /* Decrement the read bytes counter */
+ NumByteToRead--;
+ }
+ }
+
+ /* Enable Acknowledgement to be ready for another reception */
+ I2C_AcknowledgeConfig(I2C1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : I2C_EE_WaitEepromStandbyState
+* Description : Wait for EEPROM Standby state
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_EE_WaitEepromStandbyState(void)
+{
+ vu16 SR1_Tmp = 0;
+
+ do
+ {
+ /* Send START condition */
+ I2C_GenerateSTART(I2C1, ENABLE);
+ /* Read I2C1 SR1 register */
+ SR1_Tmp = I2C_ReadRegister(I2C1, I2C_Register_SR1);
+ /* Send EEPROM address for write */
+ I2C_Send7bitAddress(I2C1, EEPROM_ADDRESS, I2C_Direction_Transmitter);
+ }while(!(I2C_ReadRegister(I2C1, I2C_Register_SR1) & 0x0002));
+
+ /* Clear AF flag */
+ I2C_ClearFlag(I2C1, I2C_FLAG_AF);
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/M24C08_EEPROM/i2c_ee.h b/src/stm32lib/examples/I2C/M24C08_EEPROM/i2c_ee.h new file mode 100755 index 0000000..d9552ab --- /dev/null +++ b/src/stm32lib/examples/I2C/M24C08_EEPROM/i2c_ee.h @@ -0,0 +1,44 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : i2c_ee.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Header for i2c_ee.c module
+********************************************************************************
+* 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.
+*******************************************************************************/
+/* Define to prevent recursive inclusion ------------------------------------ */
+#ifndef __I2C_EE_H
+#define __I2C_EE_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* The M24C08W contains 4 blocks (128byte each) with the adresses below: E2 = 0 */
+/* EEPROM Addresses defines */
+//#define EEPROM_Block0_ADDRESS 0xA0 /* E2 = 0 */
+#define EEPROM_Block1_ADDRESS 0xA2 /* E2 = 0 */
+//#define EEPROM_Block2_ADDRESS 0xA4 /* E2 = 0 */
+//#define EEPROM_Block3_ADDRESS 0xA6 /* E2 = 0 */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void I2C_EE_Init(void);
+void I2C_EE_ByteWrite(u8* pBuffer, u8 WriteAddr);
+void I2C_EE_PageWrite(u8* pBuffer, u8 WriteAddr, u8 NumByteToWrite);
+void I2C_EE_BufferWrite(u8* pBuffer, u8 WriteAddr, u16 NumByteToWrite);
+void I2C_EE_BufferRead(u8* pBuffer, u8 ReadAddr, u16 NumByteToRead);
+void I2C_EE_WaitEepromStandbyState(void);
+
+#endif /* __I2C_EE_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
+
+
diff --git a/src/stm32lib/examples/I2C/M24C08_EEPROM/main.c b/src/stm32lib/examples/I2C/M24C08_EEPROM/main.c new file mode 100755 index 0000000..89be1ce --- /dev/null +++ b/src/stm32lib/examples/I2C/M24C08_EEPROM/main.c @@ -0,0 +1,230 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "i2c_ee.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define EEPROM_WriteAddress1 0x05
+#define EEPROM_ReadAddress1 0x05
+#define BufferSize1 (countof(Tx1_Buffer)-1)
+#define BufferSize2 (countof(Tx2_Buffer)-1)
+#define EEPROM_WriteAddress2 (EEPROM_WriteAddress1 + BufferSize1)
+#define EEPROM_ReadAddress2 (EEPROM_ReadAddress1 + BufferSize1)
+
+/* Private macro -------------------------------------------------------------*/
+#define countof(a) (sizeof(a) / sizeof(*(a)))
+
+/* Private variables ---------------------------------------------------------*/
+u8 Tx1_Buffer[] = "/* STM32F10x I2C Firmware ";
+u8 Tx2_Buffer[] = "Library Example */";
+u8 Rx1_Buffer[BufferSize1], Rx2_Buffer[BufferSize2];
+volatile TestStatus TransferStatus1 = FAILED, TransferStatus2 = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private functions ---------------------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength);
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* Initialize the I2C EEPROM driver ----------------------------------------*/
+ I2C_EE_Init();
+
+ /* First write in the memory followed by a read of the written data --------*/
+ /* Write on I2C EEPROM from EEPROM_WriteAddress1 */
+ I2C_EE_BufferWrite(Tx1_Buffer, EEPROM_WriteAddress1, BufferSize1);
+
+ /* Read from I2C EEPROM from EEPROM_ReadAddress1 */
+ I2C_EE_BufferRead(Rx1_Buffer, EEPROM_ReadAddress1, BufferSize1);
+
+ /* Check if the data written to the memory is read correctly */
+ TransferStatus1 = Buffercmp(Tx1_Buffer, Rx1_Buffer, BufferSize1);
+ /* TransferStatus1 = PASSED, if the transmitted and received data
+ to/from the EEPROM are the same */
+ /* TransferStatus1 = FAILED, if the transmitted and received data
+ to/from the EEPROM are different */
+
+ /* Wait for EEPROM standby state */
+ I2C_EE_WaitEepromStandbyState();
+
+ /* Second write in the memory followed by a read of the written data -------*/
+ /* Write on I2C EEPROM from EEPROM_WriteAddress2 */
+ I2C_EE_BufferWrite(Tx2_Buffer, EEPROM_WriteAddress2, BufferSize2);
+
+ /* Read from I2C EEPROM from EEPROM_ReadAddress2 */
+ I2C_EE_BufferRead(Rx2_Buffer, EEPROM_ReadAddress2, BufferSize2);
+
+ /* Check if the data written to the memory is read correctly */
+ TransferStatus2 = Buffercmp(Tx2_Buffer, Rx2_Buffer, BufferSize2);
+ /* TransferStatus2 = PASSED, if the transmitted and received data
+ to/from the EEPROM are the same */
+ /* TransferStatus2 = FAILED, if the transmitted and received data
+ to/from the EEPROM are different */
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* GPIOB Periph clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
+ /* I2C1 Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/M24C08_EEPROM/readme.txt b/src/stm32lib/examples/I2C/M24C08_EEPROM/readme.txt new file mode 100755 index 0000000..d1b9c50 --- /dev/null +++ b/src/stm32lib/examples/I2C/M24C08_EEPROM/readme.txt @@ -0,0 +1,79 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the I2C and M24C08 EEPROM communication example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a basic example of how to use the I2C software library
+and an associate I2C EEPROM driver to communicate with an M24C08 EEPROM.
+I2C1 is configured in Master transmitter during write operation and in Master
+receiver during read operation from I2C EEPROM.
+The speed is set to the maximum frequency of 400kHz. This value is defined in
+the I2c_ee.c file, which could be in the range of 0 to 400KHZ.
+One I2C EEPROM Block address where the program will write the buffer have to be
+selected from the four address available and defined in the I2c_ee.h file.
+The EEPROM address where the program start the write and the read operations is
+defined in the main.c file.
+
+First, the contents of Tx1_Buffer are written to the EEPROM_WriteAddress1 and the
+written data are read. The written and the read buffers data are then compared.
+Following the read operation, the program wait that the EEPROM reverts to its
+Standby state. A second write operation is, then, performed and this time, Tx2_Buffer
+is written to EEPROM_WriteAddress2, which represents the address just after the last
+written one in the first write. After completion of the second write operation, the
+written data are read. The contents of the written and the read buffers are compared.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+i2c_ee.c I2C EEPROM driver
+i2c_ee.h Header for the i2c_ee.c file
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards with addition of the following hardware connection:
+ - Connect I2C1 SCL pin (PB.06) to I2C EEPROM SCL (pin6)
+ - Connect I2C1 SDA pin (PB.07) to I2C EEPROM SDA (pin5)
+ - Check that a pull-up resistor is connected on one I2C SDA pin
+ - Check that a pull-up resistor is connected on one I2C SCL pin
+ - Connect I2C EEPROM Vcc (pin8) to Vdd
+ - Connect I2C EEPROM Vss (pin4) to Vss
+
+Note: The pull-up resitors are already implemented on the STM3210B-EVAL and
+ STM3210E-EVAL evaluation boards.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_i2c.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_gpio.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/I2C/M24C08_EEPROM/stm32f10x_conf.h b/src/stm32lib/examples/I2C/M24C08_EEPROM/stm32f10x_conf.h new file mode 100755 index 0000000..080839c --- /dev/null +++ b/src/stm32lib/examples/I2C/M24C08_EEPROM/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+#define _I2C
+#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/M24C08_EEPROM/stm32f10x_it.c b/src/stm32lib/examples/I2C/M24C08_EEPROM/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/I2C/M24C08_EEPROM/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/M24C08_EEPROM/stm32f10x_it.h b/src/stm32lib/examples/I2C/M24C08_EEPROM/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/I2C/M24C08_EEPROM/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/SMBus/main.c b/src/stm32lib/examples/I2C/SMBus/main.c new file mode 100755 index 0000000..0db942f --- /dev/null +++ b/src/stm32lib/examples/I2C/SMBus/main.c @@ -0,0 +1,258 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define I2C1_SLAVE_ADDRESS7 0x10
+#define I2C2_SLAVE_ADDRESS7 0x30
+#define SMBusDefaultHeader 0xC2
+#define Command 0x01
+#define ClockSpeed 20000
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+I2C_InitTypeDef I2C_InitStructure;
+vu8 ReceivedCommand = 0, PECValue = 0;
+volatile FlagStatus Status = RESET;
+ErrorStatus HSEStartUpStatus;
+
+/* Private functions ---------------------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* Enable I2C1 and I2C2 ----------------------------------------------------*/
+ I2C_Cmd(I2C1, ENABLE);
+ I2C_Cmd(I2C2, ENABLE);
+
+ /* I2C1 configuration: SMBus Host ------------------------------------------*/
+ I2C_InitStructure.I2C_Mode = I2C_Mode_SMBusHost;
+ I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2;
+ I2C_InitStructure.I2C_OwnAddress1 = I2C1_SLAVE_ADDRESS7;
+ I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
+ I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
+ I2C_InitStructure.I2C_ClockSpeed = ClockSpeed;
+ I2C_Init(I2C1, &I2C_InitStructure);
+
+ /* I2C2 configuration: SMBus Device ----------------------------------------*/
+ I2C_InitStructure.I2C_Mode = I2C_Mode_SMBusDevice;
+ I2C_InitStructure.I2C_OwnAddress1 = I2C2_SLAVE_ADDRESS7;
+ I2C_Init(I2C2, &I2C_InitStructure);
+
+ /* Enable I2C2 ARP */
+ I2C_ARPCmd(I2C2, ENABLE);
+
+ /* Enable I2C1 and I2C2 PEC Transmission */
+ I2C_CalculatePEC(I2C1, ENABLE);
+ I2C_CalculatePEC(I2C2, ENABLE);
+
+ /*----- Transmission Phase -----*/
+ /* Send I2C1 START condition */
+ I2C_GenerateSTART(I2C1, ENABLE);
+ /* Test on I2C1 EV5 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_MODE_SELECT));
+ /* Send Slave address */
+ I2C_Send7bitAddress(I2C1, SMBusDefaultHeader, I2C_Direction_Transmitter);
+ /* Test on I2C1 EV6 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED));
+
+ /* Get I2C2 SMBDEFAULT flag status */
+ Status = I2C_GetFlagStatus(I2C2, I2C_FLAG_SMBDEFAULT);
+
+ /* Send Command */
+ I2C_SendData(I2C1, Command);
+ /* Clear ADDR flag */
+ I2C_ClearFlag(I2C2, I2C_FLAG_ADDR);
+ /* Wait for I2C2 received data */
+ while(!I2C_GetFlagStatus(I2C2, I2C_FLAG_RXNE));
+ /* Store received data on I2C2 */
+ ReceivedCommand = I2C_ReceiveData(I2C2);
+ /* Test on I2C1 EV8 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_TRANSMITTED));
+
+ /* Enable Transfer PEC next for I2C1 and I2C2 */
+ I2C_TransmitPEC(I2C1, ENABLE);
+ I2C_TransmitPEC(I2C2, ENABLE);
+ /* Wait for I2C2 received data */
+ while(!I2C_GetFlagStatus(I2C2, I2C_FLAG_RXNE));
+ /* Store received PEC on I2C2 */
+ PECValue = I2C_ReceiveData(I2C2);
+ /* Test on I2C1 EV8 and clear it */
+ while(!I2C_CheckEvent(I2C1, I2C_EVENT_MASTER_BYTE_TRANSMITTED));
+
+ /* Send I2C1 STOP Condition */
+ I2C_GenerateSTOP(I2C1, ENABLE);
+ /* Test on I2C2 EV4 and clear it */
+ while(!I2C_CheckEvent(I2C2, I2C_EVENT_SLAVE_STOP_DETECTED));
+ /* Clear I2C2 STOPF flag */
+ I2C_ClearFlag(I2C2, I2C_FLAG_STOPF);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+/* Enable peripheral clocks --------------------------------------------------*/
+ /* GPIOB Periph clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
+ /* I2C1 and I2C2 Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1 | RCC_APB1Periph_I2C2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure I2C1 pins: SCL and SDA ----------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* Configure I2C2 pins: SCL and SDA ----------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/SMBus/readme.txt b/src/stm32lib/examples/I2C/SMBus/readme.txt new file mode 100755 index 0000000..15e395a --- /dev/null +++ b/src/stm32lib/examples/I2C/SMBus/readme.txt @@ -0,0 +1,75 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the I2C SMBus mode example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to send an ARP command from I2C1 to
+I2C2 in SMBus mode.
+
+After configuring the I2C1 and I2C2 as SMBus Host and Device, respectively, both
+I2Cs are enabled. The PEC calculation is enabled for both I2Cs.
+The ARP capability is enabled for the slave I2C2. Following the start condition
+generation, the master I2C1 sends the SMBus default header and I2C2 responds by
+setting its SMBDEFAULT flag. The master I2C1 then issues the "Prepare to ARP"
+command to the slave I2C2. PEC transfer is then enabled for both I2Cs, and the
+PEC value received on I2C2 is stored into the PEC_Value variable.
+
+A correct transmission leads to obtaining the following variable values:
+ - Status = 0x01 (the flag SMBDEFAULT has been set)
+ - ReceivedCommand = 0x01 (the Command value has been correctly received)
+
+The communication clock speed is set to 200KHz.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+ - Connect I2C1 SCL pin (PB.06) to I2C2 SCL pin (PB.10)
+ - Connect I2C1 SDA pin (PB.07) to I2C2 SDA pin (PB.11)
+ - Check that a pull-up resistor is connected on one I2C SDA pin
+ - Check that a pull-up resistor is connected on one I2C SCL pin
+
+Note: The pull-up resitors are already implemented on the STM3210B-EVAL and
+ STM3210E-EVAL evaluation boards.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_i2c.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_gpio.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/I2C/SMBus/stm32f10x_conf.h b/src/stm32lib/examples/I2C/SMBus/stm32f10x_conf.h new file mode 100755 index 0000000..2281b25 --- /dev/null +++ b/src/stm32lib/examples/I2C/SMBus/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+#define _I2C
+#define _I2C1
+#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/SMBus/stm32f10x_it.c b/src/stm32lib/examples/I2C/SMBus/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/I2C/SMBus/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2C/SMBus/stm32f10x_it.h b/src/stm32lib/examples/I2C/SMBus/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/I2C/SMBus/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2S/Interrupt/main.c b/src/stm32lib/examples/I2S/Interrupt/main.c new file mode 100755 index 0000000..7e6a062 --- /dev/null +++ b/src/stm32lib/examples/I2S/Interrupt/main.c @@ -0,0 +1,356 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+I2S_InitTypeDef I2S_InitStructure;
+u16 I2S2_Buffer_Tx[32] = {0x0102, 0x0304, 0x0506, 0x0708, 0x090A, 0x0B0C,
+ 0x0D0E, 0x0F10, 0x1112, 0x1314, 0x1516, 0x1718,
+ 0x191A, 0x1B1C, 0x1D1E, 0x1F20, 0x2122, 0x2324,
+ 0x2526, 0x2728, 0x292A, 0x2B2C, 0x2D2E, 0x2F30,
+ 0x3132, 0x3334, 0x3536, 0x3738, 0x393A, 0x3B3C,
+ 0x3D3E, 0x3F40};
+
+u16 I2S3_Buffer_Rx[32];
+volatile u8 TxIdx = 0, RxIdx = 0;
+volatile TestStatus TransferStatus1 = FAILED, TransferStatus2 = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u16* pBuffer1, u16* pBuffer2, u16 BufferLength);
+TestStatus Buffercmp24bits(u16* pBuffer1, u16* pBuffer2, u16 BufferLength);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* I2S peripheral configuration */
+ I2S_InitStructure.I2S_Standard = I2S_Standard_Phillips;
+ I2S_InitStructure.I2S_DataFormat = I2S_DataFormat_16bextended;
+ I2S_InitStructure.I2S_MCLKOutput = I2S_MCLKOutput_Disable;
+ I2S_InitStructure.I2S_AudioFreq = I2S_AudioFreq_48k;
+ I2S_InitStructure.I2S_CPOL = I2S_CPOL_Low;
+
+ /* I2S2 Master Transmitter to I2S3 Slave Receiver communication -----------*/
+ /* I2S2 configuration */
+ I2S_InitStructure.I2S_Mode = I2S_Mode_MasterTx;
+ I2S_Init(SPI2, &I2S_InitStructure);
+
+ /* I2S3 configuration */
+ I2S_InitStructure.I2S_Mode = I2S_Mode_SlaveRx;
+ I2S_Init(SPI3, &I2S_InitStructure);
+
+ /* Enable the I2S2 TxE interrupt */
+ SPI_I2S_ITConfig(SPI2, SPI_I2S_IT_TXE, ENABLE);
+
+ /* Enable the I2S3 RxNE interrupt */
+ SPI_I2S_ITConfig(SPI3, SPI_I2S_IT_RXNE, ENABLE);
+
+ /* Enable the I2S3 */
+ I2S_Cmd(SPI3, ENABLE);
+
+ /* Enable the I2S2 */
+ I2S_Cmd(SPI2, ENABLE);
+
+ /* Wait the end of communication */
+ while (RxIdx < 32)
+ {}
+
+ TransferStatus1 = Buffercmp(I2S3_Buffer_Rx, I2S2_Buffer_Tx, 32);
+ /* TransferStatus1 = PASSED, if the data transmitted from I2S2 and received by
+ I2S3 are the same
+ TransferStatus1 = FAILED, if the data transmitted from I2S2 and received by
+ I2S3 are different */
+
+ /* Reinitialize the buffers */
+ for (RxIdx = 0; RxIdx < 32; RxIdx++)
+ {
+ I2S3_Buffer_Rx[RxIdx] = 0;
+ }
+ TxIdx = 0;
+ RxIdx = 0;
+
+ /* I2S peripheral configuration */
+ I2S_InitStructure.I2S_Standard = I2S_Standard_Phillips;
+ I2S_InitStructure.I2S_DataFormat = I2S_DataFormat_24b;
+ I2S_InitStructure.I2S_MCLKOutput = I2S_MCLKOutput_Disable;
+ I2S_InitStructure.I2S_AudioFreq = I2S_AudioFreq_16k;
+ I2S_InitStructure.I2S_CPOL = I2S_CPOL_Low;
+
+ /* I2S2 Master Transmitter to I2S3 Slave Receiver communication -----------*/
+ /* I2S2 configuration */
+ I2S_InitStructure.I2S_Mode = I2S_Mode_MasterTx;
+ I2S_Init(SPI2, &I2S_InitStructure);
+
+ /* I2S3 configuration */
+ I2S_InitStructure.I2S_Mode = I2S_Mode_SlaveRx;
+ I2S_Init(SPI3, &I2S_InitStructure);
+
+ /* Enable the I2S2 TxE interrupt */
+ SPI_I2S_ITConfig(SPI2, SPI_I2S_IT_TXE, ENABLE);
+
+ /* Enable the I2S3 RxNE interrupt */
+ SPI_I2S_ITConfig(SPI3, SPI_I2S_IT_RXNE, ENABLE);
+
+ /* Enable the I2S3 */
+ I2S_Cmd(SPI3, ENABLE);
+
+ /* Enable the I2S2 */
+ I2S_Cmd(SPI2, ENABLE);
+
+ /* Wait the end of communication */
+ while (RxIdx < 32)
+ {}
+
+ TransferStatus2 = Buffercmp24bits(I2S3_Buffer_Rx, I2S2_Buffer_Tx, 32);
+ /* TransferStatus2 = PASSED, if the data transmitted from I2S2 and received by
+ I2S3 are the same
+ TransferStatus2 = FAILED, if the data transmitted from I2S2 and received by
+ I2S3 are different */
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK/2 */
+ RCC_PCLK2Config(RCC_HCLK_Div2);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* Enable peripheral clocks --------------------------------------------------*/
+ /* GPIOA, GPIOB and AFIO clocks enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB |
+ RCC_APB2Periph_AFIO, ENABLE);
+
+ /* SPI2 and SPI3 clocks enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2 | RCC_APB1Periph_SPI3, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Disable the JTAG interface and enable the SWJ interface */
+ GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE);
+
+ /* Configure SPI2 pins: CK, WS and SD */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12 | GPIO_Pin_13 | GPIO_Pin_15;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* Configure SPI3 pins: CK and SD */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3 | GPIO_Pin_5;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* Configure SPI3 pins: WS */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_15;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_0);
+
+ /* SPI2 IRQ Channel configuration */
+ NVIC_InitStructure.NVIC_IRQChannel = SPI2_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* SPI3 IRQ channel configuration */
+ NVIC_InitStructure.NVIC_IRQChannel = SPI3_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u16* pBuffer1, u16* pBuffer2, u16 BufferLength)
+{
+ while (BufferLength--)
+ {
+ if (*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp24bits
+* Description : Compares two buffers in 24 bits data format.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp24bits(u16* pBuffer1, u16* pBuffer2, u16 BufferLength)
+{
+ while (BufferLength--)
+ {
+ if (*pBuffer1 != *pBuffer2)
+ {
+ if (*pBuffer1 != (*pBuffer2 & 0xFF00))
+ {
+ return FAILED;
+ }
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2S/Interrupt/readme.txt b/src/stm32lib/examples/I2S/Interrupt/readme.txt new file mode 100755 index 0000000..760bd7d --- /dev/null +++ b/src/stm32lib/examples/I2S/Interrupt/readme.txt @@ -0,0 +1,86 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the I2S Interrupt Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to set a communication between two
+SPIs in I2S mode using interrupts and performing a transfer from Master to Slave.
+
+In the first step, I2S2 is configured as master transmitter and I2S3 as slave
+reciever and both are in Phillips standard configuration with 16bit extended to
+32 bit data packet and 48KHz audio frequnecy.
+
+The I2S2 transmit interrupt and the I2S3 receive interrupt are both enabled. And
+in these interrupts subroutines, the I2S2_Buffer_Tx is transmitted and the received
+values are loaded in the I2S3_Buffer_Rx buffer. Only the significant 16 MSBs are
+sent and received, while the 32 packet remaining 16 LSBs are filled with 0 values
+and don't generate any interrupt.
+
+Once the transfer is completed a comparison is done and TransferStatus1 gives the
+data transfer status where it is PASSED if transmitted and received data are the
+same otherwise it is FAILED.
+
+In the second step both peripherals are configured in I2S Phillips standard 24 bits
+data length in 32 bits packets and 16KHz audio frequency. The interrupts are
+enabled and the transfer is performed from the I2S2 master to the I2S3 slave.
+The 24 bits are transmited then the 8 remaining LSBs are filled automatically
+with 0 values.
+
+Once the transfer is completed a comparison is done (on the 24 MSBs only, the 8
+LSBs are replaced by 0) and TransferStatus2 gives the data transfer status where
+it is PASSED if transmitted and received data are the same otherwise it is FAILED.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board and can be
+easily tailored to any other hardware.
+
+ - Connect I2S2 WS (PB.12) pin to I2S3 WS (PA.15) pin
+ - Connect I2S2 CK (PB.13) pin to I2S3 CK (PB.03) pin
+ - Connect I2S2 SD (PB.15) pin to I2S3 SD (PB.05) pin
+
+Since some SPI3/I2S3 pins are shared with JTAG pins (SPI3_NSS/I2S3_WS with JTDI
+and SPI3_SCK/I2S3_CK with JTDO), they are not controlled by the I/O controller
+and are reserved for JTAG usage (after each Reset).
+For this purpose prior to configure the SPI3/I2S3 pins, the user has to disable
+the JTAG and use the SWD interface (when debugging the application), or disable
+both JTAG/SWD interfaces (for standalone application).
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_spi.c
+ + stm32f10x_rcc.c
+ + stm32f10x_gpio.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/I2S/Interrupt/stm32f10x_conf.h b/src/stm32lib/examples/I2S/Interrupt/stm32f10x_conf.h new file mode 100755 index 0000000..f877270 --- /dev/null +++ b/src/stm32lib/examples/I2S/Interrupt/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+#define _SPI
+//#define _SPI1
+#define _SPI2
+#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+#define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2S/Interrupt/stm32f10x_it.c b/src/stm32lib/examples/I2S/Interrupt/stm32f10x_it.c new file mode 100755 index 0000000..661ccab --- /dev/null +++ b/src/stm32lib/examples/I2S/Interrupt/stm32f10x_it.c @@ -0,0 +1,765 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+extern u16 I2S2_Buffer_Tx[32], I2S3_Buffer_Rx[32];
+extern vu8 TxIdx, RxIdx;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+ /* Check the interrupt source */
+ if (SPI_I2S_GetITStatus(SPI2, SPI_I2S_IT_TXE) == SET)
+ {
+ /* Send a data from I2S2 */
+ SPI_I2S_SendData(SPI2, I2S2_Buffer_Tx[TxIdx++]);
+ }
+
+ /* Check the end of buffer transfer */
+ if (RxIdx == 32)
+ {
+ /* Disable the I2S2 TXE interrupt to end the communication */
+ SPI_I2S_ITConfig(SPI2, SPI_I2S_IT_TXE, DISABLE);
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+ /* Check the interrupt source */
+ if (SPI_I2S_GetITStatus(SPI3, SPI_I2S_IT_RXNE) == SET)
+ {
+ /* Store the I2S3 received data in the relative data table */
+ I2S3_Buffer_Rx[RxIdx++] = SPI_I2S_ReceiveData(SPI3);
+ }
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2S/Interrupt/stm32f10x_it.h b/src/stm32lib/examples/I2S/Interrupt/stm32f10x_it.h new file mode 100755 index 0000000..58da1cc --- /dev/null +++ b/src/stm32lib/examples/I2S/Interrupt/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2S/SPI_I2S_Switch/main.c b/src/stm32lib/examples/I2S/SPI_I2S_Switch/main.c new file mode 100755 index 0000000..72ad8a8 --- /dev/null +++ b/src/stm32lib/examples/I2S/SPI_I2S_Switch/main.c @@ -0,0 +1,383 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Local includes ------------------------------------------------------------*/
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define BufferSize 32
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+I2S_InitTypeDef I2S_InitStructure;
+SPI_InitTypeDef SPI_InitStructure;
+u16 I2S2_Buffer_Tx[BufferSize] = {0x0102, 0x0304, 0x0506, 0x0708, 0x090A, 0x0B0C,
+ 0x0D0E, 0x0F10, 0x1112, 0x1314, 0x1516, 0x1718,
+ 0x191A, 0x1B1C, 0x1D1E, 0x1F20, 0x2122, 0x2324,
+ 0x2526, 0x2728, 0x292A, 0x2B2C, 0x2D2E, 0x2F30,
+ 0x3132, 0x3334, 0x3536, 0x3738, 0x393A, 0x3B3C,
+ 0x3D3E, 0x3F40};
+
+u16 SPI2_Buffer_Tx[BufferSize] = {0x5152, 0x5354, 0x5556, 0x5758, 0x595A, 0x5B5C,
+ 0x5D5E, 0x5F60, 0x6162, 0x6364, 0x6566, 0x6768,
+ 0x696A, 0x6B6C, 0x6D6E, 0x6F70, 0x7172, 0x7374,
+ 0x7576, 0x7778, 0x797A, 0x7B7C, 0x7D7E, 0x7F80,
+ 0x8182, 0x8384, 0x8586, 0x8788, 0x898A, 0x8B8C,
+ 0x8D8E, 0x8F90};
+
+u16 I2S3_Buffer_Rx[BufferSize];
+u16 SPI3_Buffer_Rx[BufferSize];
+u8 TxIdx = 0, RxIdx = 0;
+volatile TestStatus TransferStatus1 = FAILED, TransferStatus2 = FAILED;
+volatile TestStatus TransferStatus3 = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private functions ---------------------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u16* pBuffer1, u16* pBuffer2, u16 BufferLength);
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* I2S peripheral configuration */
+ I2S_InitStructure.I2S_Standard = I2S_Standard_Phillips;
+ I2S_InitStructure.I2S_DataFormat = I2S_DataFormat_16bextended;
+ I2S_InitStructure.I2S_MCLKOutput = I2S_MCLKOutput_Disable;
+ I2S_InitStructure.I2S_AudioFreq = I2S_AudioFreq_48k;
+ I2S_InitStructure.I2S_CPOL = I2S_CPOL_Low;
+
+ /* I2S2 Master Transmitter to I2S3 Slave Receiver communication ------------*/
+ /* I2S2 configuration */
+ I2S_InitStructure.I2S_Mode = I2S_Mode_MasterTx;
+ I2S_Init(SPI2, &I2S_InitStructure);
+
+ /* I2S3 configuration */
+ I2S_InitStructure.I2S_Mode = I2S_Mode_SlaveRx;
+ I2S_Init(SPI3, &I2S_InitStructure);
+
+ /* Enable the I2S3 */
+ I2S_Cmd(SPI3, ENABLE);
+
+ /* Enable the I2S2 */
+ I2S_Cmd(SPI2, ENABLE);
+
+ /* Begin the communication in I2S mode */
+ while (RxIdx < BufferSize)
+ {
+ /* Wait the Tx buffer to be empty */
+ while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_TXE) == RESET)
+ {}
+ /* Send a data from I2S2 */
+ SPI_I2S_SendData(SPI2, I2S2_Buffer_Tx[TxIdx++]);
+
+ /* Wait the Rx buffer to be full */
+ while (SPI_I2S_GetFlagStatus(SPI3, SPI_I2S_FLAG_RXNE) == RESET)
+ {}
+ /* Store the I2S3 received data in the relative data table */
+ I2S3_Buffer_Rx[RxIdx++] = SPI_I2S_ReceiveData(SPI3);
+ }
+
+ TransferStatus1 = Buffercmp(I2S3_Buffer_Rx, I2S2_Buffer_Tx, BufferSize);
+ /* TransferStatus1 = PASSED, if the data transmitted from I2S2 and received by
+ I2S3 are the same
+ TransferStatus1 = FAILED, if the data transmitted from I2S2 and received by
+ I2S3 are different */
+
+ /* Reset TxIdx, RxIdx indexes */
+ TxIdx = 0;
+ RxIdx = 0;
+
+ /* Switch to SPI mode communication ----------------------------------------*/
+ /* SPI2 configuration */
+ SPI_InitStructure.SPI_Direction = SPI_Direction_1Line_Tx;
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
+ SPI_InitStructure.SPI_DataSize = SPI_DataSize_16b;
+ SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
+ SPI_InitStructure.SPI_CPHA = SPI_CPHA_2Edge;
+ SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
+ SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_4;
+ SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
+ SPI_InitStructure.SPI_CRCPolynomial = 7;
+ SPI_Init(SPI2, &SPI_InitStructure);
+
+ /* SPI3 configuration ------------------------------------------------------*/
+ SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_RxOnly;
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Slave;
+ SPI_Init(SPI3, &SPI_InitStructure);
+
+ /* Enable SPI3 */
+ SPI_Cmd(SPI3, ENABLE);
+ /* Enable SPI2 */
+ SPI_Cmd(SPI2, ENABLE);
+
+ /* Begin the communication in SPI mode */
+ while (RxIdx < BufferSize)
+ {
+ /* Wait the Tx buffer to be empty */
+ while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_TXE) == RESET)
+ {}
+ /* Send a data from SPI2 */
+ SPI_I2S_SendData(SPI2, SPI2_Buffer_Tx[TxIdx++]);
+
+ /* Wait the Rx buffer to be full */
+ while (SPI_I2S_GetFlagStatus(SPI3, SPI_I2S_FLAG_RXNE) == RESET)
+ {}
+ /* Store the SPI3 received data in the relative data table */
+ SPI3_Buffer_Rx[RxIdx++] = SPI_I2S_ReceiveData(SPI3);
+ }
+
+ TransferStatus2 = Buffercmp(SPI3_Buffer_Rx, SPI2_Buffer_Tx, BufferSize);
+ /* TransferStatus2 = PASSED, if the data transmitted from SPI2 and received by
+ SPI3 are the same
+ TransferStatus2 = FAILED, if the data transmitted from SPI2 and received by
+ SPI3 are different */
+
+ /* Reset TxIdx, RxIdx indexes and receive table values */
+ for (TxIdx = 0; TxIdx < BufferSize; TxIdx++)
+ {
+ I2S3_Buffer_Rx[TxIdx] = 0;
+ }
+
+ TxIdx = 0;
+ RxIdx = 0;
+
+ /* I2S2 Slave Transmitter to I2S3 Master Receiver communication ------------*/
+ /* I2S2 configuration */
+ I2S_InitStructure.I2S_Mode = I2S_Mode_SlaveTx;
+ I2S_Init(SPI2, &I2S_InitStructure);
+
+ /* I2S3 configuration */
+ I2S_InitStructure.I2S_Mode = I2S_Mode_MasterRx;
+ I2S_Init(SPI3, &I2S_InitStructure);
+
+ /* Wait the Tx buffer to be empty */
+ while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_TXE) == RESET)
+ {}
+ /* Prepare the first data to be sent from the slave */
+ SPI_I2S_SendData(SPI2, I2S2_Buffer_Tx[TxIdx++]);
+
+ /* Enable the I2S2 */
+ I2S_Cmd(SPI2, ENABLE);
+
+ /* Enable the I2S3 */
+ I2S_Cmd(SPI3, ENABLE);
+
+ /* Begin the communication in I2S mode */
+ while (RxIdx < BufferSize)
+ {
+ /* Wait the Rx buffer to be full */
+ while (SPI_I2S_GetFlagStatus(SPI3, SPI_I2S_FLAG_RXNE) == RESET)
+ {}
+ /* Store the I2S3 received data in the relative data table */
+ I2S3_Buffer_Rx[RxIdx++] = SPI_I2S_ReceiveData(SPI3);
+
+ /* Wait the Tx buffer to be empty */
+ while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_TXE) == RESET)
+ {}
+ /* Send a data from I2S2 */
+ SPI_I2S_SendData(SPI2, I2S2_Buffer_Tx[TxIdx++]);
+ }
+
+ TransferStatus3 = Buffercmp(I2S3_Buffer_Rx, I2S2_Buffer_Tx, BufferSize);
+ /* TransferStatus3 = PASSED, if the data transmitted from I2S2 and received by
+ I2S3 are the same
+ TransferStatus3 = FAILED, if the data transmitted from I2S2 and received by
+ I2S3 are different */
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK/2 */
+ RCC_PCLK2Config(RCC_HCLK_Div2);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* Enable peripheral clocks --------------------------------------------------*/
+ /* GPIOA, GPIOB and AFIO clocks enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB |
+ RCC_APB2Periph_AFIO, ENABLE);
+
+ /* SPI2 and SPI3 clocks enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2 | RCC_APB1Periph_SPI3, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Disable the JTAG interface and enable the SWJ interface */
+ GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE);
+
+ /* Configure SPI2 pins: CK, WS and SD ---------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12 | GPIO_Pin_13 | GPIO_Pin_15;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* Configure SPI3 pins: CK and SD ------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3 | GPIO_Pin_5;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* Configure SPI3 pins: WS -------------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_15;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u16* pBuffer1, u16* pBuffer2, u16 BufferLength)
+{
+ while (BufferLength--)
+ {
+ if (*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2S/SPI_I2S_Switch/readme.txt b/src/stm32lib/examples/I2S/SPI_I2S_Switch/readme.txt new file mode 100755 index 0000000..3706ec5 --- /dev/null +++ b/src/stm32lib/examples/I2S/SPI_I2S_Switch/readme.txt @@ -0,0 +1,90 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the SPI_I2S_Switch Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to set a communication between two
+SPIs in I2S mode, and how to switch between SPI and I2S modes, performing a
+transfer from Master to Slave in I2S modes then a transfer from master to slave
+in SPI mode and finally a transfer from Slave to Master in I2S mode.
+
+I2S2 is configured as master transmitter and I2S3 as slave reciever and both are
+in Phillips standard configuration with 16bit data size in 32bit packet length
+and 48KHz audio frequnecy.
+
+In the first phase, the master I2S2 starts the I2S2_Buffer_Tx transfer while the
+slave I2S3 receieves and loads the values in I2S3_Buffer_Rx. Once the transfer is
+completed a comparison is done and TransferStatus1 gives the data transfer status
+where it is PASSED if transmitted and received data are the same otherwise it is
+FAILED.
+
+In the second step, both preripherals are configured in SPI modes (simplex
+communication) and SPI2_Buffer_Tx transfer is performed in simplex mode from SPI2 to
+SPI3.Once the transfer is completed a comparison is done and TransferStatus2 gives
+the data transfer status where it is PASSED if transmitted and received data are
+the same otherwise it is FAILED.
+As the master/slave mode is managed by software (the master is the clock (CK and WS)
+generator), this allows to I2S2 to become slave transmitter and I2S3 to become master
+receiver whithout hardware modification.
+
+In the third step, the slave I2S2 prepares the first data to be sent before the
+master is enabled. Once the master is enabled, the clocks are released from the
+master and the data are released on the slave. Once the transfer is completed
+a comparison is done and TransferStatus3 gives the data transfer status where it
+is PASSED if transmitted and received data are the same otherwise it is FAILED.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board and can be
+easily tailored to any other hardware.
+
+ - Connect I2S2 WS (PB.12) pin to I2S3 WS (PA.15) pin
+ - Connect I2S2 CK (PB.13) pin to I2S3 CK (PB.03) pin
+ - Connect I2S2 SD (PB.15) pin to I2S3 SD (PB.05) pin
+
+Since some SPI3/I2S3 pins are shared with JTAG pins (SPI3_NSS/I2S3_WS with JTDI
+and SPI3_SCK/I2S3_CK with JTDO), they are not controlled by the I/O controller
+and are reserved for JTAG usage (after each Reset).
+For this purpose prior to configure the SPI3/I2S3 pins, the user has to disable
+the JTAG and use the SWD interface (when debugging the application), or disable
+both JTAG/SWD interfaces (for standalone application).
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_spi.c
+ + stm32f10x_rcc.c
+ + stm32f10x_gpio.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/I2S/SPI_I2S_Switch/stm32f10x_conf.h b/src/stm32lib/examples/I2S/SPI_I2S_Switch/stm32f10x_conf.h new file mode 100755 index 0000000..f877270 --- /dev/null +++ b/src/stm32lib/examples/I2S/SPI_I2S_Switch/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+#define _SPI
+//#define _SPI1
+#define _SPI2
+#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+#define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2S/SPI_I2S_Switch/stm32f10x_it.c b/src/stm32lib/examples/I2S/SPI_I2S_Switch/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/I2S/SPI_I2S_Switch/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/I2S/SPI_I2S_Switch/stm32f10x_it.h b/src/stm32lib/examples/I2S/SPI_I2S_Switch/stm32f10x_it.h new file mode 100755 index 0000000..58da1cc --- /dev/null +++ b/src/stm32lib/examples/I2S/SPI_I2S_Switch/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/IWDG/main.c b/src/stm32lib/examples/IWDG/main.c new file mode 100755 index 0000000..d2bc6c8 --- /dev/null +++ b/src/stm32lib/examples/IWDG/main.c @@ -0,0 +1,281 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+void GPIO_Configuration(void);
+void EXTI_Configuration(void);
+void SysTick_Configuration(void);
+void Delay(vu32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* GPIO configuration */
+ GPIO_Configuration();
+
+ /* Check if the system has resumed from IWDG reset */
+ if (RCC_GetFlagStatus(RCC_FLAG_IWDGRST) != RESET)
+ {/* IWDGRST flag set */
+ /* Set GPIO_LED pin 6 */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_6);
+
+ /* Clear reset flags */
+ RCC_ClearFlag();
+ }
+ else
+ {/* IWDGRST flag is not set */
+ /* Reset GPIO_LED pin 6 */
+ GPIO_ResetBits(GPIO_LED, GPIO_Pin_6);
+ }
+
+ /* Configure Key Button EXTI Line to generate an interrupt on falling edge */
+ EXTI_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure SysTick to generate an interrupt each 250ms */
+ SysTick_Configuration();
+
+ /* IWDG timeout equal to 280 ms (the timeout may varies due to LSI frequency
+ dispersion) */
+ /* Enable write access to IWDG_PR and IWDG_RLR registers */
+ IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable);
+
+ /* IWDG counter clock: 40KHz(LSI) / 32 = 1.25 KHz */
+ IWDG_SetPrescaler(IWDG_Prescaler_32);
+
+ /* Set counter reload value to 349 */
+ IWDG_SetReload(349);
+
+ /* Reload IWDG counter */
+ IWDG_ReloadCounter();
+
+ /* Enable IWDG (the LSI oscillator will be enabled by hardware) */
+ IWDG_Enable();
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 0 wait state */
+ FLASH_SetLatency(FLASH_Latency_0);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK */
+ RCC_PCLK1Config(RCC_HCLK_Div1);
+
+ /* Select HSE as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_HSE);
+
+ /* Wait till HSE is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x04)
+ {}
+ }
+
+ /* Enable Key Button GPIO Port, GPIO_LED and AFIO clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_KEY_BUTTON | RCC_APB2Periph_GPIO_LED
+ | RCC_APB2Periph_AFIO, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure GPIO_LED pin 6 and pin 7 as Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ /* Configure Key Button GPIO Pin as input floating (Key Button EXTI Line) */
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_KEY_BUTTON;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIO_KEY_BUTTON, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : EXTI_Configuration
+* Description : Configures EXTI Line9.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_Configuration(void)
+{
+ EXTI_InitTypeDef EXTI_InitStructure;
+
+ /* Connect Key Button EXTI Line to Key Button GPIO Pin */
+ GPIO_EXTILineConfig(GPIO_PORT_SOURCE_KEY_BUTTON, GPIO_PIN_SOURCE_KEY_BUTTON);
+
+ /* Configure Key Button EXTI Line to generate an interrupt on falling edge */
+ EXTI_ClearITPendingBit(EXTI_LINE_KEY_BUTTON);
+ EXTI_InitStructure.EXTI_Line = EXTI_LINE_KEY_BUTTON;
+ EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
+ EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+ EXTI_Init(&EXTI_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Configure one bit for preemption priority */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
+
+ /* Enable the EXTI9_5 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = EXTI9_5_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Set SysTick interrupt vector Preemption Priority to 1 */
+ NVIC_SystemHandlerPriorityConfig(SystemHandler_SysTick, 1, 0);
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for (; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {}
+}
+#endif
+
+/*******************************************************************************
+* Function Name : SysTick_Configuration
+* Description : Configures SysTick to generate an interrupt each 250ms.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTick_Configuration(void)
+{
+ /* Select HCLK/8 as SysTick clock source */
+ SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK_Div8);
+
+ /* SysTick interrupt each 250ms with counter clock equal to 1MHz */
+ SysTick_SetReload(250000);
+
+ /* Enable the SysTick Counter */
+ SysTick_CounterCmd(SysTick_Counter_Enable);
+
+ /* Enable the SysTick Interrupt */
+ SysTick_ITConfig(ENABLE);
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/IWDG/platform_config.h b/src/stm32lib/examples/IWDG/platform_config.h new file mode 100755 index 0000000..4d96ed9 --- /dev/null +++ b/src/stm32lib/examples/IWDG/platform_config.h @@ -0,0 +1,56 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+//#define USE_STM3210B_EVAL
+#define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+ #define GPIO_KEY_BUTTON GPIOB
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOB
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_9
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line9
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOB
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource9
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+ #define GPIO_KEY_BUTTON GPIOG
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOG
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_8
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line8
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOG
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource8
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/IWDG/readme.txt b/src/stm32lib/examples/IWDG/readme.txt new file mode 100755 index 0000000..8ce6e44 --- /dev/null +++ b/src/stm32lib/examples/IWDG/readme.txt @@ -0,0 +1,88 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the IWDG Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to reload at regulate period the IWDG counter using the
+SysTick interrupt. The IWDG timeout is set to 280 ms (the timeout may varies due
+to LSI frequency dispersion).
+
+SysTick is configured to generate an interrupt every 250 ms. In the SysTick interrupt
+service routine (ISR), the IWDG counter is reloaded to prevent an IWDG reset, and
+a specific GPIO pin is toggled.
+An EXTI is connected to a specific GPIO pin and configured to generate an interrupt
+on its falling edge.
+In the NVIC, this EXTI line corresspondant interrupt vector is enabled with a
+priority equal to 0, and the SysTick interrupt vector priority is set to 1
+(EXTI IT > SysTick IT).
+
+The EXTI Line is used to simulate a software failure: when the EXTI Line event is
+triggered (by pressing the Key push-button on the board), the corresponding interrupt
+is served. In the ISR, the GPIO pin turns off and the EXTI line pending bit is
+not cleared. So the CPU executes the EXTI line ISR indefinitely and the SysTick
+ISR is never entered (IWDG counter not reloaded).
+As a result, when the IWDG counter reaches 00h, the IWDG generates a reset.
+If the IWDG reset is generated, an other specific GPIO pin is turned on after
+the system resumes operation.
+
+If the EXTI Line event does not occur, the IWDG counter is indefinitely reloaded in
+the SysTick ISR, which prevents any IWDG reset.
+
+In this example the system is clocked by the high-speed external (HSE) clock (8 MHz).
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1 and LD2 leds connected respectively to PC.06 and PC.07 pins, and the
+ KEY push button connected to PB.09 pin.
+
+ + STM3210E-EVAL
+ - Use LD1 and LD2 leds connected respectively to PF.06 and PF.07 pins, and the
+ KEY push button connected to PG.08 pin.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_iwdg.c
+ + stm32f10x_flash.c
+ + stm32f10x_exti.c
+ + stm32f10x_systick.c
+
+- Link all compiled files and load your image into target memory
+- Run the example in standalone mode (without debugger connection)
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/IWDG/stm32f10x_conf.h b/src/stm32lib/examples/IWDG/stm32f10x_conf.h new file mode 100755 index 0000000..42b99e2 --- /dev/null +++ b/src/stm32lib/examples/IWDG/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+#define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/IWDG/stm32f10x_it.c b/src/stm32lib/examples/IWDG/stm32f10x_it.c new file mode 100755 index 0000000..2f0c024 --- /dev/null +++ b/src/stm32lib/examples/IWDG/stm32f10x_it.c @@ -0,0 +1,758 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "platform_config.h"
+
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+ /* Reload IWDG counter */
+ IWDG_ReloadCounter();
+
+ /* Toggle GPIO_LED pin 7 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_7, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_7)));
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+ if (EXTI_GetITStatus(EXTI_LINE_KEY_BUTTON) != RESET)
+ {
+ /* Reset GPIO_LED pin 7 */
+ GPIO_ResetBits(GPIO_LED, GPIO_Pin_7);
+
+ /* As EXTI_LINE_KEY_BUTTON pending bit is not cleared, the CPU will execute indefinitely
+ this ISR and when the IWDG counter reaches 00h the IWDG reset occurs */
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/IWDG/stm32f10x_it.h b/src/stm32lib/examples/IWDG/stm32f10x_it.h new file mode 100755 index 0000000..58da1cc --- /dev/null +++ b/src/stm32lib/examples/IWDG/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/Lib_DEBUG/main.c b/src/stm32lib/examples/Lib_DEBUG/main.c new file mode 100755 index 0000000..2433d49 --- /dev/null +++ b/src/stm32lib/examples/Lib_DEBUG/main.c @@ -0,0 +1,268 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include <stdio.h>
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+void GPIO_Configuration(void);
+void USART_Configuration(void);
+
+#ifdef __GNUC__
+ /* With GCC/RAISONANCE, small printf (option LD Linker->Libraries->Small printf
+ set to 'Yes') calls __io_putchar() */
+ #define PUTCHAR_PROTOTYPE int __io_putchar(int ch)
+#else
+ #define PUTCHAR_PROTOTYPE int fputc(int ch, FILE *f)
+#endif /* __GNUC__ */
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+ GPIO_InitTypeDef GPIOA_InitStructure;
+
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* Configure the system clocks */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIOs */
+ GPIO_Configuration();
+
+ /* Configure the USART1 */
+ USART_Configuration();
+
+ printf("\r\n STM32F10x Firmware Library compiled in DEBUG mode... \n\r");
+ printf("...Run-time checking enabled \n\r");
+
+ /* Simulate wrong parameter passed to library function ---------------------*/
+ /* To enable SPI1 clock, RCC_APB2PeriphClockCmd function must be used and
+ not RCC_APB1PeriphClockCmd */
+ RCC_APB1PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE);
+
+ /* Some member of GPIOA_InitStructure structure are not initialized */
+ GPIOA_InitStructure.GPIO_Pin = GPIO_Pin_6;
+ GPIOA_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ /* GPIOA_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; */
+ GPIO_Init(GPIOA, &GPIOA_InitStructure);
+
+ while (1)
+ {
+ }
+
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number */
+
+ printf("\n\r Wrong parameter value detected on\r\n");
+ printf(" file %s\r\n", file);
+ printf(" line %d\r\n", line);
+
+ /* Infinite loop */
+ /* while (1)
+ {
+ } */
+}
+#endif
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable USART1 and GPIOA clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure USART1 Tx (PA.09) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART1 Rx (PA.10) as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : USART_Configuration
+* Description : Configures the USART1.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_Configuration(void)
+{
+ USART_InitTypeDef USART_InitStructure;
+
+/* USART1 configuration ------------------------------------------------------*/
+ /* USART1 configured as follow:
+ - BaudRate = 115200 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+ */
+ USART_InitStructure.USART_BaudRate = 115200;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_No;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+
+ USART_Init(USART1, &USART_InitStructure);
+
+ /* Enable USART1 */
+ USART_Cmd(USART1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : PUTCHAR_PROTOTYPE
+* Description : Retargets the C library printf function to the USART.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+PUTCHAR_PROTOTYPE
+{
+ /* Place your implementation of fputc here */
+ /* e.g. write a character to the USART */
+ USART_SendData(USART1, (u8) ch);
+
+ /* Loop until the end of transmission */
+ while(USART_GetFlagStatus(USART1, USART_FLAG_TC) == RESET)
+ {
+ }
+
+ return ch;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/Lib_DEBUG/readme.txt b/src/stm32lib/examples/Lib_DEBUG/readme.txt new file mode 100755 index 0000000..5584d97 --- /dev/null +++ b/src/stm32lib/examples/Lib_DEBUG/readme.txt @@ -0,0 +1,83 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the Lib_DEBUG Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example demonstrates the STM32F10x Firmware Library DEBUG mode.
+
+To enter Debug mode you have to define the label DEBUG in the stm32f10x_conf.h file.
+This creates a pointer to the peripheral structure in SRAM. Debugging consequently
+becomes easier and all register settings can be obtained by dumping a peripheral variable.
+When the Debug mode is selected, the assert_param macro is expanded and run-time checking
+is enabled in the firmware library code. The run-time checking allows checking that
+all the library functions input value lies within the parameter allowed values.
+
+The associated program simulates wrong parameter passed to library function and the
+source of the error is printed on Hyperterminal (through USART1).
+
+
+Note:
+The Debug mode increases the code size and reduces the code performance. For this
+reason, it is recommended to used it only when debugging the application and to
+remove it from the final application code.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+ + STM3210B-EVAL
+ - Connect a null-modem female/female RS232 cable between the DB9 connector
+ CN6 and PC serial port.
+
+ + STM3210E-EVAL
+ - Connect a null-modem female/female RS232 cable between the DB9 connector
+ CN12 and PC serial port.
+
+
+ - Hyperterminal configuration:
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - BaudRate = 115200 baud
+ - flow control: None
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_usart.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/Lib_DEBUG/stm32f10x_conf.h b/src/stm32lib/examples/Lib_DEBUG/stm32f10x_conf.h new file mode 100755 index 0000000..2255e93 --- /dev/null +++ b/src/stm32lib/examples/Lib_DEBUG/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+#define DEBUG 1
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/Lib_DEBUG/stm32f10x_it.c b/src/stm32lib/examples/Lib_DEBUG/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/Lib_DEBUG/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/Lib_DEBUG/stm32f10x_it.h b/src/stm32lib/examples/Lib_DEBUG/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/Lib_DEBUG/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/CM3_LPModes/main.c b/src/stm32lib/examples/NVIC/CM3_LPModes/main.c new file mode 100755 index 0000000..ce11bb1 --- /dev/null +++ b/src/stm32lib/examples/NVIC/CM3_LPModes/main.c @@ -0,0 +1,344 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+//#define WFISLEEPONEXIT
+#define WFISLEEPNOW
+//#define WFESEVONPEND
+//#define WFESEVONEVENT
+//#define RTC_Alarm_WFEWakeUp
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+EXTI_InitTypeDef EXTI_InitStructure;
+GPIO_InitTypeDef GPIO_InitStructure;
+NVIC_InitTypeDef NVIC_InitStructure;
+vu32 LowPowerMode = 0;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void EXTI_Configuration(void);
+void Delay(vu32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* Configure the system clocks */
+ RCC_Configuration();
+
+ /* Configure GPIOs */
+ GPIO_Configuration();
+
+ /* Configures the EXTI Lines */
+ EXTI_Configuration();
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
+
+ NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ NVIC_InitStructure.NVIC_IRQChannel = EXTI0_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
+ NVIC_Init(&NVIC_InitStructure);
+
+ while (1)
+ {
+ if(LowPowerMode == 1)
+ {
+ LowPowerMode = 0;
+
+ /* Toggle GPIO_LED pin 6 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_6, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_6)));
+
+ #ifdef WFISLEEPONEXIT
+ NVIC_SystemLPConfig(NVIC_LP_SLEEPONEXIT, ENABLE);
+ #endif
+
+ #ifdef WFISLEEPNOW
+ NVIC_SystemLPConfig(NVIC_LP_SLEEPONEXIT, DISABLE);
+ __WFI();
+ #endif
+
+ #ifdef WFESEVONPEND
+ NVIC_SystemLPConfig(NVIC_LP_SEVONPEND, ENABLE);
+ /* Boost the execution priority to 0: no further exception can be asserted */
+ NVIC_SETPRIMASK();
+ #ifdef RTC_Alarm_WFEWakeUp
+ /* Set the RTC Alarm interrupt after 6s */
+ RTC_SetAlarm(0xFFFFFFFA);
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+ /* Set the Counter to 0xFFFFFFF5 */
+ RTC_SetCounter(0xFFFFFFF5);
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+ #endif
+ __WFE();
+ #endif
+
+ #ifdef WFESEVONEVENT
+ NVIC_SystemLPConfig(NVIC_LP_SEVONPEND, DISABLE);
+ #ifdef RTC_Alarm_WFEWakeUp
+ /* Set the RTC Alarm interrupt after 6s */
+ RTC_SetAlarm(0xFFFFFFFA);
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+ /* Set the Counter to 0xFFFFFFF5 */
+ RTC_SetCounter(0xFFFFFFF5);
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+ #endif
+ __WFE();
+ #endif
+ }
+
+ Delay(0xFFFFF);
+
+ /* Toggle GPIO_LED pin 9 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_9, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_9)));
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* GPIOA, GPIOC, GPIO KEY Button, GPIO_LED and AFIO clocks enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIO_KEY_BUTTON |
+ RCC_APB2Periph_GPIO_LED | RCC_APB2Periph_GPIOC |
+ RCC_APB2Periph_AFIO, ENABLE);
+
+#ifdef RTC_Alarm_WFEWakeUp
+ /* Enable the PWR and BKP Clocks */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE);
+
+ /* Configure the EXTI Line 17 as Event */
+ EXTI_StructInit(&EXTI_InitStructure);
+ EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Event;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
+ EXTI_InitStructure.EXTI_Line = EXTI_Line17;
+ EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+ EXTI_Init(&EXTI_InitStructure);
+
+ /* Allow access to BKP Domain */
+ PWR_BackupAccessCmd(ENABLE);
+
+ /* Reset Backup Domain */
+ BKP_DeInit();
+ /* Enable LSE */
+ RCC_LSEConfig(RCC_LSE_ON);
+ /* Wait till LSE is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_LSERDY) == RESET)
+ {
+ }
+
+ /* Select LSE as RTC Clock Source */
+ RCC_RTCCLKConfig(RCC_RTCCLKSource_LSE);
+
+ /* Enable the RTC Clock */
+ RCC_RTCCLKCmd(ENABLE);
+ /* Wait for APB registers synchronisation */
+ RTC_WaitForSynchro();
+
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+ /* Set the RTC time base to 1s */
+ RTC_SetPrescaler(32767);
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+#endif
+
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the used GPIO pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_StructInit(&GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_KEY_BUTTON;
+ GPIO_Init(GPIO_KEY_BUTTON, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : EXTI_Configuration
+* Description : Configures the used EXTI lines.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_Configuration(void)
+{
+ /* Connect EXTI Line0 to PA.00 */
+ GPIO_EXTILineConfig(GPIO_PortSourceGPIOA, GPIO_PinSource0);
+
+ /* Configure EXTI Line0 to generate an interrupt on falling edge */
+ EXTI_InitStructure.EXTI_Line = EXTI_Line0;
+ EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
+ EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+ EXTI_Init(&EXTI_InitStructure);
+
+
+ /* Connect EXTI Line13 to PC.13 */
+ GPIO_EXTILineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource13);
+
+ /* Configure EXTI Line13 to generate an event on falling edge */
+ EXTI_InitStructure.EXTI_Line = EXTI_Line13;
+ EXTI_Init(&EXTI_InitStructure);
+
+
+ /* Connect Key Button EXTI Line to GPIO Key Button Pin */
+ GPIO_EXTILineConfig(GPIO_PORT_SOURCE_KEY_BUTTON, GPIO_PIN_SOURCE_KEY_BUTTON);
+
+ /* Configure Key Button EXTI Line to generate an event on falling edge */
+ EXTI_InitStructure.EXTI_Line = EXTI_LINE_KEY_BUTTON;
+ EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Event;
+ EXTI_Init(&EXTI_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for(; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/CM3_LPModes/platform_config.h b/src/stm32lib/examples/NVIC/CM3_LPModes/platform_config.h new file mode 100755 index 0000000..3deb7ba --- /dev/null +++ b/src/stm32lib/examples/NVIC/CM3_LPModes/platform_config.h @@ -0,0 +1,56 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+ #define GPIO_KEY_BUTTON GPIOB
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOB
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_9
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line9
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOB
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource9
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+ #define GPIO_KEY_BUTTON GPIOG
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOG
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_8
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line8
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOG
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource8
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/CM3_LPModes/readme.txt b/src/stm32lib/examples/NVIC/CM3_LPModes/readme.txt new file mode 100755 index 0000000..94d2ef3 --- /dev/null +++ b/src/stm32lib/examples/NVIC/CM3_LPModes/readme.txt @@ -0,0 +1,137 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the NVIC CM3 Low Power Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example describes how to use the NVIC firmware library to demonstrate the
+Cortex-M3 low power modes capabilities (WFE and WFI).
+
+This example uses three EXTI lines(Wakeup button EXTI Line, Key button EXTI Line
+& Tamper button EXTI Line)to generate interrupts and event on each falling edge.
+The Wakeup button EXTI Line and Tamper button EXTI Line are configured in
+interrupt mode and the Key button EXTI Line in event mode. The user has to select
+which low power mode would execute through a five define in the main code.
+
+These choices are:
+
+ - Wait For Interrupt (WFI) Sleep On Exit: in this mode the WFI instruction is
+ excecuted automatically on an exception Return. The exception will be executed
+ if has enough priority to run and the core will return in the WFI mode.
+ To run this behaviour proceed as following:
+
+ * Choose the #WFISLEEPONEXIT define and comment others defines
+ * run the example
+ * The Wakeup button EXTI Line toggles LD4.
+ * Push the Tamper button, the SLEEPONEXIT function is selected
+ Any edge on the Wakeup button EXTI Line or Tamper button EXTI Line will
+ execute the EXTI interrupt, when exit from the ISR the core will enter WFI
+ mode. Any time you push the Wakeup button the core exit from WFI mode,
+ LD4 is toggled then the core enters again in WFI mode.
+ This behavior is repeated in an infinite loop.
+
+ - Wait For Interrupt (WFI) Sleep Now: in this mode the WFI instruction is
+ excecuted directly. To run this behaviour proceed as following:
+
+ * Choose the #WFISLEEPNOW define and comment others defines
+ * run the example
+ * The Tamper button EXTI Line will toggle LD1 and put the core in the WFI mode.
+ * To wakeup the Core use the Wakeup button that will toggle the LD3.
+ This behavior is repeated in an infinite loop.
+
+ - Wait For Event (WFE) SEV ON PEND: in this mode the WFE instruction is excecuted
+ directly and the main instruction stream (execution priority) is boosted by the
+ register PRIMASK (main priority = 0).
+ To run this behaviour proceed as following:
+
+ * Choose the #WFESEVONPEND define and comment others defines
+ * run the example
+ * The Tamper button EXTI Line will boost the execution priority to 0 (no
+ interrupt will be executed after due to the priority boosting), toggle
+ LD1 and put the core in WFE mode.
+ * To wakeUp the Core use the Wakeup button that will not toggle the LD3 but
+ will only wakeup the core from the WFE (SEV ON PEND).
+ This EXTI Line interrupt has passed from unpended state to a pended state
+ which wakeup the core from the WFE.
+ * To wakeup the core also you can use theTamper button configured in event
+ mode.
+ * if the #RTC_Alarm_WFEWakeUp define is enabled, the RTC alarm will wakeUp
+ the Core after 6 seconds (if none of Tamper button EXTI Line and Key
+ button EXTI Line was used before this delay to wakeUp the Core)
+
+ - Wait For Event (WFE) SEV ON EVENT: in this mode the WFE instruction is
+ excecuted directly. To run this behaviour proceed as following:
+
+ * Choose the #WFESEVONEVENT define and comment others defines
+ * run the example
+ * The Tamper button EXTI Line will toggle LD1 and put the core in the WFE mode.
+ * To wakeup the Core use the Wakeup button that will toggle the LD3.
+ * To wakeup the core also you can use the Key button configured in event mode.
+ * if the #RTC_Alarm_WFEWakeUp define is enabled, the RTC alarm will wakeUp
+ the Core after 6 seconds (if none of Tamper button EXTI Line and Key button
+ EXTI Line was used before this delay to wakeup the Core)
+ This behavior is repeated in an infinite loop.
+
+LD4 is toggled to indicate whether the MCU is in RUN or in low power mode.
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PC.06, PC.07, PC.08
+ and PC.09 pins
+ - Use the Key push-button connected to pin PB.09 (EXTI Line9).
+ - Use the Wakeup push-button connected to pin PA.00 (EXTI Line0).
+ - Use the Tamper push-button connected to pin PC.13 (EXTI Line13).
+
+ + STM3210E-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PF.06, PF0.7, PF.08
+ and PF.09 pins
+ - Use the Key push-button connected to pin PG.08 (EXTI Line8).
+ - Use the Wakeup push-button connected to pin PA.00 (EXTI Line0).
+ - Use the Tamper push-button connected to pin PC.13 (EXTI Line13).
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_exti.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_rtc.c
+ + stm32f10x_pwr.c
+ + stm32f10x_bkp.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/NVIC/CM3_LPModes/stm32f10x_conf.h b/src/stm32lib/examples/NVIC/CM3_LPModes/stm32f10x_conf.h new file mode 100755 index 0000000..a04dca1 --- /dev/null +++ b/src/stm32lib/examples/NVIC/CM3_LPModes/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/CM3_LPModes/stm32f10x_it.c b/src/stm32lib/examples/NVIC/CM3_LPModes/stm32f10x_it.c new file mode 100755 index 0000000..4413799 --- /dev/null +++ b/src/stm32lib/examples/NVIC/CM3_LPModes/stm32f10x_it.c @@ -0,0 +1,825 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+extern vu32 LowPowerMode;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+ /* Clear EXTI line0 pending bit */
+ EXTI_ClearITPendingBit(EXTI_Line0);
+
+ /* Toggle GPIO_LED pin 8 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_8, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_8)));
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+ if(EXTI_GetITStatus(EXTI_Line13) != RESET)
+ {
+ /* Clear EXTI line13 pending bit */
+ EXTI_ClearITPendingBit(EXTI_Line13);
+
+ LowPowerMode = 1;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/CM3_LPModes/stm32f10x_it.h b/src/stm32lib/examples/NVIC/CM3_LPModes/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/NVIC/CM3_LPModes/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/DMA_WFIMode/main.c b/src/stm32lib/examples/NVIC/DMA_WFIMode/main.c new file mode 100755 index 0000000..130c0a8 --- /dev/null +++ b/src/stm32lib/examples/NVIC/DMA_WFIMode/main.c @@ -0,0 +1,352 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define USART1_DR_Address 0x40013804
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+NVIC_InitTypeDef NVIC_InitStructure;
+DMA_InitTypeDef DMA_InitStructure;
+
+vu32 LowPowerMode = 0;
+u16 DST_Buffer[10]= {0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void EXTI_Configuration(void);
+void DMA_Configuration(void);
+void USART_Configuration(void);
+u8 Buffercmp16(u16* pBuffer1, u16* pBuffer2, u16 BufferLength);
+void Delay(vu32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* Configure the system clocks */
+ RCC_Configuration();
+
+ /* Configure GPIOs */
+ GPIO_Configuration();
+
+ /* Configures the EXTI Lines */
+ EXTI_Configuration();
+
+ /* Configures the DMA Channel */
+ DMA_Configuration();
+
+ /* Configures the USART1 */
+ USART_Configuration();
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
+
+ /* Enable the DMA1 Channel 5 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel5_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Enable the EXTI9_5 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = EXTI9_5_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
+ NVIC_Init(&NVIC_InitStructure);
+
+ while (1)
+ {
+ if(LowPowerMode == 1)
+ {
+
+ GPIO_ResetBits(GPIO_LED, GPIO_Pin_7 | GPIO_Pin_8);
+
+ /* Request to enter WFI mode */
+ __WFI();
+ LowPowerMode = 0;
+ }
+
+ Delay(0xFFFFF);
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_6, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_6)));
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable USART1, GPIOA, GPIO_LED, GPIO_KEY_BUTTON and AFIO clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA |
+ RCC_APB2Periph_GPIO_LED | RCC_APB2Periph_GPIO_KEY_BUTTON |
+ RCC_APB2Periph_AFIO, ENABLE);
+
+ /* DMA1 clock enable */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the used GPIO pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure GPIO_LED Pin 6, GPIO_LED Pin 7 and GPIO_LED Pin 8 as
+ Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 |GPIO_Pin_7 | GPIO_Pin_8;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ /* Configure USART1 Rx (PA.10) as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure GPIO KEY Button Pin as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_KEY_BUTTON;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIO_KEY_BUTTON, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : EXTI_Configuration
+* Description : Configures the used EXTI line.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_Configuration(void)
+{
+ EXTI_InitTypeDef EXTI_InitStructure;
+
+ /* Connect KEY Button EXTI Line to GPIO KEY Button Pin */
+ GPIO_EXTILineConfig(GPIO_PORT_SOURCE_KEY_BUTTON, GPIO_PIN_SOURCE_KEY_BUTTON);
+
+ /* Configure KEY Button EXTI Line to generate an interrupt on falling edge */
+ EXTI_InitStructure.EXTI_Line = EXTI_LINE_KEY_BUTTON;
+ EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
+ EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+ EXTI_Init(&EXTI_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : DMA_Configuration
+* Description : Configures the used DMA Channel.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_Configuration(void)
+{
+ DMA_InitTypeDef DMA_InitStructure;
+
+ /* DMA1 Channel5 Config */
+ DMA_DeInit(DMA1_Channel5);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = USART1_DR_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)DST_Buffer;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = 10;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA1_Channel5, &DMA_InitStructure);
+
+ /* Enable Channel5 Transfer complete interrupt */
+ DMA_ITConfig(DMA1_Channel5, DMA_IT_TC, ENABLE);
+
+ /* DMA1 Channel5 enable */
+ DMA_Cmd(DMA1_Channel5, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : USART_Configuration
+* Description : Configures the USART1.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_Configuration(void)
+{
+ USART_InitTypeDef USART_InitStructure;
+
+/* USART1 configuration ------------------------------------------------------*/
+ /* USART1 configured as follow:
+ - BaudRate = 9600 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+ */
+ USART_InitStructure.USART_BaudRate = 9600;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_No;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+
+ USART_Init(USART1, &USART_InitStructure);
+
+ USART_DMACmd(USART1, USART_DMAReq_Rx, ENABLE);
+
+ /* Enable the USART1 */
+ USART_Cmd(USART1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp16
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : 0: pBuffer1 identical to pBuffer2
+* 1: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+u8 Buffercmp16(u16* pBuffer1, u16* pBuffer2, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer1 != *pBuffer2)
+ {
+ return 1;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+ return 0;
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for(; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/DMA_WFIMode/platform_config.h b/src/stm32lib/examples/NVIC/DMA_WFIMode/platform_config.h new file mode 100755 index 0000000..3deb7ba --- /dev/null +++ b/src/stm32lib/examples/NVIC/DMA_WFIMode/platform_config.h @@ -0,0 +1,56 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+ #define GPIO_KEY_BUTTON GPIOB
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOB
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_9
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line9
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOB
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource9
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+ #define GPIO_KEY_BUTTON GPIOG
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOG
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_8
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line8
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOG
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource8
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/DMA_WFIMode/readme.txt b/src/stm32lib/examples/NVIC/DMA_WFIMode/readme.txt new file mode 100755 index 0000000..ee99fcd --- /dev/null +++ b/src/stm32lib/examples/NVIC/DMA_WFIMode/readme.txt @@ -0,0 +1,103 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the NVIC DMA in WFI mode Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to enters the system to WFI mode with DMA transfer enabled
+and wake-up from this mode by the DMA End of Transfer interrupt.
+
+In the associated software, the system clock is set to 72 MHz, the DMA1 Channel5
+is configured to transfer 10 data from the USART1 data register to a predefined
+buffer, DST_Buffer, and to generate an interrupt at the end of the transfer.
+The USART1 receives data from Hyperterminal.
+A LED1 is toggled with a frequency depending on the system
+clock, this is used to indicate whether the MCU is in WFI or RUN mode.
+
+A falling edge on the selected EXTI Line will put the core in the WFI mode, causing the
+led pin to stop toggling.
+To wake-up from WFI mode you have to send the sequence (0, 1, 2, 3, 4, 5, 6, 7, 8, 9)
+from the Hyperterminal to the USART1. These bytes will be transferred by the DMA from
+the USART1 receive data register to the predefined buffer, then generates an interrupt
+which exits the system from WFI mode.
+The LED1 restarts toggling and a LED2 will toggle if the buffer is correctly received
+else a LED3 is toggled.
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PC.06, PC.07, PC.08
+ and PC.09 pins
+ - The USART1 signals (Rx, Tx) must be connected to a DB9 connector using a RS232
+ transceiver.
+ - Connect a null-modem female/female RS232 cable between the DB9 connector,
+ CN6 on STM3210B-EVAL board, and PC serial port.
+ - Hyperterminal configuration:
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - BaudRate = 9600 baud
+ - flow control: None
+ - Use the Key push-button connected to pin PB.09 (EXTI Line9).
+
+ + STM3210E-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PF.06, PF0.7, PF.08
+ and PF.09 pins
+ - The USART1 signals (Rx, Tx) must be connected to a DB9 connector using a RS232
+ transceiver.
+ - Connect a null-modem female/female RS232 cable between the DB9 connector,
+ CN12 on STM3210E-EVAL board, and PC serial port.
+ - Hyperterminal configuration:
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - BaudRate = 9600 baud
+ - flow control: None
+ - Use the Key push-button connected to pin PG.08 (EXTI Line8).
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_exti.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_dma.c
+ + stm32f10x_usart.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/NVIC/DMA_WFIMode/stm32f10x_conf.h b/src/stm32lib/examples/NVIC/DMA_WFIMode/stm32f10x_conf.h new file mode 100755 index 0000000..c286a47 --- /dev/null +++ b/src/stm32lib/examples/NVIC/DMA_WFIMode/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/DMA_WFIMode/stm32f10x_it.c b/src/stm32lib/examples/NVIC/DMA_WFIMode/stm32f10x_it.c new file mode 100755 index 0000000..6aae663 --- /dev/null +++ b/src/stm32lib/examples/NVIC/DMA_WFIMode/stm32f10x_it.c @@ -0,0 +1,843 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+u8 TestStatus = 0;
+u16 SRC_Buffer[10] = {0x30, 0x31, 0x32, 0x33, 0x34, 0x35, 0x36, 0x37, 0x38, 0x39};
+extern u16 DST_Buffer[10];
+extern vu32 LowPowerMode;
+extern u8 Buffercmp16(u16*, u16*, u16);
+extern void DMA_Configuration(void);
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+ if(DMA_GetITStatus(DMA1_IT_TC5))
+ {
+ DMA_ClearITPendingBit(DMA1_IT_TC5);
+
+ /* Check the received buffer */
+ TestStatus = Buffercmp16(SRC_Buffer, DST_Buffer, 10);
+
+ if(TestStatus == 0)
+ {
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_7, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_7)));
+ }
+ else
+ {
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_8, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_8)));
+ }
+
+ /* Re-configure DMA1 */
+ DMA_Configuration();
+ }
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+ if(EXTI_GetITStatus(EXTI_LINE_KEY_BUTTON) != RESET)
+ {
+ EXTI_ClearITPendingBit(EXTI_LINE_KEY_BUTTON);
+
+ LowPowerMode = 1;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/DMA_WFIMode/stm32f10x_it.h b/src/stm32lib/examples/NVIC/DMA_WFIMode/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/NVIC/DMA_WFIMode/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/IRQ_Channels/main.c b/src/stm32lib/examples/NVIC/IRQ_Channels/main.c new file mode 100755 index 0000000..47b3df9 --- /dev/null +++ b/src/stm32lib/examples/NVIC/IRQ_Channels/main.c @@ -0,0 +1,261 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+NVIC_InitTypeDef NVIC_InitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void TIM_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* Configure the system clocks */
+ RCC_Configuration();
+
+ /* Configure GPIOs */
+ GPIO_Configuration();
+
+ /* Configure TIMs */
+ TIM_Configuration();
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Configure one bit for preemption priority */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
+
+ /* Enable the TIM2 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Enable the TIM3 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = TIM3_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Enable the TIM4 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = TIM4_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
+ NVIC_Init(&NVIC_InitStructure);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable GPIO_LED clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_LED, ENABLE);
+
+ /* Enable TIM2, TIM3 and TIM4 clocks */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 |
+ RCC_APB1Periph_TIM4, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the used GPIO pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure GPIO_LED pin 6, GPIO_LED pin 7, GPIO_LED pin 8 as output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : TIM_Configuration
+* Description : Configures the used Timers.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_Configuration(void)
+{
+ TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+ TIM_OCInitTypeDef TIM_OCInitStructure;
+
+ /* TIM2 configuration */
+ TIM_TimeBaseStructure.TIM_Period = 0x4AF;
+ TIM_TimeBaseStructure.TIM_Prescaler = 0xEA5F;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0x0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseStructure.TIM_RepetitionCounter = 0x0000;
+ TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
+
+ TIM_OCStructInit(&TIM_OCInitStructure);
+ /* Output Compare Timing Mode configuration: Channel1 */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Timing;
+ TIM_OCInitStructure.TIM_Pulse = 0x0;
+ TIM_OC1Init(TIM2, &TIM_OCInitStructure);
+
+ /* TIM3 configuration */
+ TIM_TimeBaseStructure.TIM_Period = 0x95F;
+
+ TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
+ /* Output Compare Timing Mode configuration: Channel1 */
+ TIM_OC1Init(TIM3, &TIM_OCInitStructure);
+
+ /* TIM4 configuration */
+ TIM_TimeBaseStructure.TIM_Period = 0xE0F;
+
+ TIM_TimeBaseInit(TIM4, &TIM_TimeBaseStructure);
+ /* Output Compare Timing Mode configuration: Channel1 */
+ TIM_OC1Init(TIM4, &TIM_OCInitStructure);
+
+ /* TIM2 enable counter */
+ TIM_Cmd(TIM2, ENABLE);
+ /* TIM3 enable counter */
+ TIM_Cmd(TIM3, ENABLE);
+ /* TIM4 enable counter */
+ TIM_Cmd(TIM4, ENABLE);
+
+ /* Immediate load of TIM2 Precaler value */
+ TIM_PrescalerConfig(TIM2, 0xEA5F, TIM_PSCReloadMode_Immediate);
+ /* Immediate load of TIM3 Precaler value */
+ TIM_PrescalerConfig(TIM3, 0xEA5F, TIM_PSCReloadMode_Immediate);
+ /* Immediate load of TIM4 Precaler value */
+ TIM_PrescalerConfig(TIM4, 0xEA5F, TIM_PSCReloadMode_Immediate);
+
+ /* Clear TIM2 update pending flag */
+ TIM_ClearFlag(TIM2, TIM_FLAG_Update);
+ /* Clear TIM3 update pending flag */
+ TIM_ClearFlag(TIM3, TIM_FLAG_Update);
+ /* Clear TIM4 update pending flag */
+ TIM_ClearFlag(TIM4, TIM_FLAG_Update);
+
+ /* Enable TIM2 Update interrupt */
+ TIM_ITConfig(TIM2, TIM_IT_Update, ENABLE);
+ /* Enable TIM3 Update interrupt */
+ TIM_ITConfig(TIM3, TIM_IT_Update, ENABLE);
+ /* Enable TIM4 Update interrupt */
+ TIM_ITConfig(TIM4, TIM_IT_Update, ENABLE);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/IRQ_Channels/platform_config.h b/src/stm32lib/examples/NVIC/IRQ_Channels/platform_config.h new file mode 100755 index 0000000..0bc5169 --- /dev/null +++ b/src/stm32lib/examples/NVIC/IRQ_Channels/platform_config.h @@ -0,0 +1,44 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/IRQ_Channels/readme.txt b/src/stm32lib/examples/NVIC/IRQ_Channels/readme.txt new file mode 100755 index 0000000..1cb8367 --- /dev/null +++ b/src/stm32lib/examples/NVIC/IRQ_Channels/readme.txt @@ -0,0 +1,69 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the NVIC IRQ Channels Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example demontrates the use of the Nested Vectored Interrupt Controller (NVIC)
+IRQ Channels configuration:
+
+- Configuration of 3 TIM (TIM2..TIM4)timers to generate an interrupt on each
+ counter update event.
+- The three timers are linked to their correspondant Update IRQ channel.
+- Assignment of a ascendant IRQ priority for each IRQ channel :
+ TIM2 has a preemption priority of 0 and TIM4 has a preemption priority of 2.
+- In each interrupt routine:
+ - TIM2 toggles a LED1 each 1s
+ - TIM3 toggles a LED2 each 2s
+ - TIM4 toggles a LED3 each 3s
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1, LD2 and LD3 leds connected respectively to PC.06, PC.07 and PC.08
+
+ + STM3210E-EVAL
+ - Use LD1, LD2 and LD3 leds connected respectively to PF.06, PF0.7 and PF.08
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_tim.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/NVIC/IRQ_Channels/stm32f10x_conf.h b/src/stm32lib/examples/NVIC/IRQ_Channels/stm32f10x_conf.h new file mode 100755 index 0000000..3a4af67 --- /dev/null +++ b/src/stm32lib/examples/NVIC/IRQ_Channels/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+#define _TIM2
+#define _TIM3
+#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/IRQ_Channels/stm32f10x_it.c b/src/stm32lib/examples/NVIC/IRQ_Channels/stm32f10x_it.c new file mode 100755 index 0000000..ef72393 --- /dev/null +++ b/src/stm32lib/examples/NVIC/IRQ_Channels/stm32f10x_it.c @@ -0,0 +1,826 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+ /* Clear TIM2 update interrupt */
+ TIM_ClearITPendingBit(TIM2, TIM_IT_Update);
+
+ /* Toggle GPIO_LED pin 6 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_6, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_6)));
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+ /* Clear TIM3 update interrupt */
+ TIM_ClearITPendingBit(TIM3, TIM_IT_Update);
+
+ /* Toggle GPIO_LED pin 7 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_7, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_7)));
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+ /* Clear TIM4 update interrupt */
+ TIM_ClearITPendingBit(TIM4, TIM_IT_Update);
+
+ /* Toggle GPIO_LED pin 8 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_8, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_8)));
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/IRQ_Channels/stm32f10x_it.h b/src/stm32lib/examples/NVIC/IRQ_Channels/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/NVIC/IRQ_Channels/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/Priority/main.c b/src/stm32lib/examples/NVIC/Priority/main.c new file mode 100755 index 0000000..711d54a --- /dev/null +++ b/src/stm32lib/examples/NVIC/Priority/main.c @@ -0,0 +1,252 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+NVIC_InitTypeDef NVIC_InitStructure;
+GPIO_InitTypeDef GPIO_InitStructure;
+EXTI_InitTypeDef EXTI_InitStructure;
+bool PreemptionOccured = FALSE;
+u8 PreemptionPriorityValue = 0;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void EXTI_Configuration(void);
+void Delay(vu32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* Configure the system clocks */
+ RCC_Configuration();
+
+ /* Configure GPIOs */
+ GPIO_Configuration();
+
+ /* Configures the EXTI Lines */
+ EXTI_Configuration();
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Configure one bit for preemption priority */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
+
+ /* Enable the EXTI0 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = EXTI0_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PreemptionPriorityValue;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Enable the EXTI9_5 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = EXTI9_5_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Configure the SysTick Handler Priority: Preemption priority and subpriority */
+ NVIC_SystemHandlerPriorityConfig(SystemHandler_SysTick, !PreemptionPriorityValue, 0);
+
+ while (1)
+ {
+ if(PreemptionOccured != FALSE)
+ {
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_6, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_6)));
+ Delay(0x5FFFF);
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_7, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_7)));
+ Delay(0x5FFFF);
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_8, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_8)));
+ Delay(0x5FFFF);
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_9, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_9)));
+ Delay(0x5FFFF);
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable GPIOA, GPIO KEY Button, GPIO_LED and AFIO Clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIO_KEY_BUTTON |
+ RCC_APB2Periph_GPIO_LED | RCC_APB2Periph_AFIO, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the used GPIO pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ /* Configure GPIO_LED pin 6, GPIO_LED pin 7, GPIO_LED pin 8 and GPIO_LED pin 9 as output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ /* Configure PA.00 as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure KEY Button GPIO pin as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_KEY_BUTTON;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIO_KEY_BUTTON, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : EXTI_Configuration
+* Description : Configures the used EXTI lines.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_Configuration(void)
+{
+ /* Connect EXTI Line0 to PA.00 */
+ GPIO_EXTILineConfig(GPIO_PortSourceGPIOA, GPIO_PinSource0);
+
+ /* Configure EXTI Line0 to generate an interrupt on falling edge */
+ EXTI_InitStructure.EXTI_Line = EXTI_Line0;
+ EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
+ EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+ EXTI_Init(&EXTI_InitStructure);
+
+ /* Connect KEY Button EXTI Line to KEY Button GPIO pin */
+ GPIO_EXTILineConfig(GPIO_PORT_SOURCE_KEY_BUTTON, GPIO_PIN_SOURCE_KEY_BUTTON);
+
+ /* Configure KEY Button EXTI Line to generate an interrupt on falling edge */
+ EXTI_InitStructure.EXTI_Line = EXTI_LINE_KEY_BUTTON;
+ EXTI_Init(&EXTI_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for(; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/Priority/platform_config.h b/src/stm32lib/examples/NVIC/Priority/platform_config.h new file mode 100755 index 0000000..3deb7ba --- /dev/null +++ b/src/stm32lib/examples/NVIC/Priority/platform_config.h @@ -0,0 +1,56 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+ #define GPIO_KEY_BUTTON GPIOB
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOB
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_9
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line9
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOB
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource9
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+ #define GPIO_KEY_BUTTON GPIOG
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOG
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_8
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line8
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOG
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource8
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/Priority/readme.txt b/src/stm32lib/examples/NVIC/Priority/readme.txt new file mode 100755 index 0000000..bd6c360 --- /dev/null +++ b/src/stm32lib/examples/NVIC/Priority/readme.txt @@ -0,0 +1,97 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the NVIC Priority Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example demontrates the use of the Nested Vectored Interrupt Controller (NVIC):
+
+- Configuration of 2 EXTI Lines (Wakeup button EXTI Line & Key button EXTI Line)
+ to generate an interrupt on each falling edge and use the SysTick interrupt.
+- These interrupts are configured with the following parameters:
+ Wakeup button EXTI Line: o PreemptionPriority = PreemptionPriorityValue
+ o SubPriority = 0
+ Key button EXTI Line: o PreemptionPriority = 0
+ o SubPriority = 1
+ SysTick Handler: o PreemptionPriority = !PreemptionPriorityValue
+ o SubPriority = 0
+First, the PreemptionPriorityValue is equal to 0, the Wakeup button EXTI Line
+has higher preemption priority than the SysTick handler.
+
+In the key button EXTI Line interrupt routine the Wakeup button EXTI Line and
+SysTick preemption priorities are inverted.
+In the Wakeup button EXTI Line interrupt routine the pending bit of the SysTick
+interrupt is set this will cause SysTick ISR to preempt the Wakeup button EXTI
+Line ISR only if it has higher preemption priority.
+
+The system behaves as following:
+1) The first time Key button EXTI Line interrupt occurs the SysTick preemption
+become higher than Wakeup button EXTI Line one. So when the Wakeup button EXTI
+Line interrupt occurs, the SysTick ISR is executed and the PreemptionOccured
+variable become TRUE and the four leds (LD1, LD2, LD3, LD4) start toggling.
+
+2) When the next Key button EXTI Line interrupt occurs the SysTick preemption
+become lower than Wakeup button EXTI Line one. So when the Wakeup button EXTI Line
+interrupt occurs, the PreemptionOccured variable became FALSE and the four leds
+(LD1, LD2, LD3, LD4) stop toggling.
+
+Then this behavior is repeated from point 1) in an infinite loop.
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PC.06, PC.07, PC.08
+ and PC.09 pins
+ - Use the Key push-button connected to pin PB.09 (EXTI Line9).
+ - Use the Wakeup push-button connected to pin PA.00 (EXTI Line0).
+
+ + STM3210E-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PF.06, PF0.7, PF.08
+ and PF.09 pins
+ - Use the Key push-button connected to pin PG.08 (EXTI Line8).
+ - Use the Wakeup push-button connected to pin PA.00 (EXTI Line0).
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_exti.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/NVIC/Priority/stm32f10x_conf.h b/src/stm32lib/examples/NVIC/Priority/stm32f10x_conf.h new file mode 100755 index 0000000..5244ccd --- /dev/null +++ b/src/stm32lib/examples/NVIC/Priority/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/Priority/stm32f10x_it.c b/src/stm32lib/examples/NVIC/Priority/stm32f10x_it.c new file mode 100755 index 0000000..2a189bd --- /dev/null +++ b/src/stm32lib/examples/NVIC/Priority/stm32f10x_it.c @@ -0,0 +1,844 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+extern bool PreemptionOccured;
+extern u8 PreemptionPriorityValue;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+ /* If the EXTI0 IRQ Handler was preempted by SysTick Handler */
+ if(NVIC_GetIRQChannelActiveBitStatus(EXTI0_IRQChannel) != RESET)
+ {
+ PreemptionOccured = TRUE;
+ }
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+ /* Generate SysTick exception */
+ NVIC_SetSystemHandlerPendingBit(SystemHandler_SysTick);
+
+ /* Clear EXTI Line0 pending bit */
+ EXTI_ClearITPendingBit(EXTI_Line0);
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+ if(EXTI_GetITStatus(EXTI_LINE_KEY_BUTTON) != RESET)
+ {
+ PreemptionPriorityValue = !PreemptionPriorityValue;
+ PreemptionOccured = FALSE;
+
+ /* Modify the EXTI0 Interrupt Preemption Priority */
+ NVIC_InitStructure.NVIC_IRQChannel = EXTI0_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PreemptionPriorityValue;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Configure the SysTick Handler Priority: Preemption priority and subpriority */
+ NVIC_SystemHandlerPriorityConfig(SystemHandler_SysTick, !PreemptionPriorityValue, 0);
+
+ /* Clear EXTI_LINE_KEY_BUTTON pending bit */
+ EXTI_ClearITPendingBit(EXTI_LINE_KEY_BUTTON);
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/Priority/stm32f10x_it.h b/src/stm32lib/examples/NVIC/Priority/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/NVIC/Priority/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/System_Handlers/main.c b/src/stm32lib/examples/NVIC/System_Handlers/main.c new file mode 100755 index 0000000..d9e6f30 --- /dev/null +++ b/src/stm32lib/examples/NVIC/System_Handlers/main.c @@ -0,0 +1,193 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+NVIC_InitTypeDef NVIC_InitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* Configure the system clocks */
+ RCC_Configuration();
+
+ /* Configure GPIOs */
+ GPIO_Configuration();
+
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* SysTick interrupt each 1 Hz with Counter clock equal to 72MHz/8 = 9MHz */
+ SysTick_SetReload(9000000);
+
+ /* Enable the SysTick Interrupt */
+ SysTick_ITConfig(ENABLE);
+
+ /* Enable the SysTick Counter */
+ SysTick_CounterCmd(SysTick_Counter_Enable);
+
+ /* Configure 2 bits for preemption priority 2 bits for subpriority */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
+
+ /* Configure the SysTick Handler Priority:
+ - preemption priority : 2
+ - subpriority : 0 */
+ NVIC_SystemHandlerPriorityConfig(SystemHandler_SysTick, 2, 0);
+
+ /* Configure the PSV Handler Priority:
+ - preemption priority : 0
+ - subpriority : 0 */
+ NVIC_SystemHandlerPriorityConfig(SystemHandler_PSV, 0, 0);
+
+ /* Configure the SVCall Handler Priority:
+ - preemption priority : 1
+ - subpriority : 0 */
+
+ NVIC_SystemHandlerPriorityConfig(SystemHandler_SVCall, 1, 0);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable GPIO_LED clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_LED, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the used GPIO pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure GPIO_LED pin 6, GPIO_LED pin 7, GPIO_LED pin 8 and GPIO_LED pin 9 as output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/System_Handlers/platform_config.h b/src/stm32lib/examples/NVIC/System_Handlers/platform_config.h new file mode 100755 index 0000000..0bc5169 --- /dev/null +++ b/src/stm32lib/examples/NVIC/System_Handlers/platform_config.h @@ -0,0 +1,44 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/System_Handlers/readme.txt b/src/stm32lib/examples/NVIC/System_Handlers/readme.txt new file mode 100755 index 0000000..c67dea2 --- /dev/null +++ b/src/stm32lib/examples/NVIC/System_Handlers/readme.txt @@ -0,0 +1,80 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the NVIC System Handlers Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example demontrates the use of the Nested Vectored Interrupt Controller (NVIC)
+and system handlers:
+
+- Assignment of a descendant system handlers preemption priority for each system
+handler:
+ - NMI has -1 as preemption priority
+ - PSV has 0 preemption priority
+ - SVCall has 1 preemption priority
+ - SysTick has 2 preemption priority
+
+- Configuration of SysTick timer to generate an interrupt on each end of count
+
+- In the Systick handler routine: a LED1 toggle each 1s and the SVC instruction
+is executed. This will activate the SVCall handler to preempt the current instruction
+stream. In the SVCall handler routine, a led connected to LED2 pin is toggling and the
+pending bit of the PSV handler is set by software.
+The PSV which has a higher preemption priority will preempt the SVCall handler and
+will toggle a LED3. Also, in this handler routine, the NMI pending bit is set and
+the NMI handler is activated and the LED4 is toggling.
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PC.06, PC.07, PC.08
+ and PC.09 pins
+
+ + STM3210E-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PF.06, PF0.7, PF.08
+ and PF.09 pins
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_systick.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/NVIC/System_Handlers/stm32f10x_conf.h b/src/stm32lib/examples/NVIC/System_Handlers/stm32f10x_conf.h new file mode 100755 index 0000000..f421f9a --- /dev/null +++ b/src/stm32lib/examples/NVIC/System_Handlers/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/System_Handlers/stm32f10x_it.c b/src/stm32lib/examples/NVIC/System_Handlers/stm32f10x_it.c new file mode 100755 index 0000000..c588064 --- /dev/null +++ b/src/stm32lib/examples/NVIC/System_Handlers/stm32f10x_it.c @@ -0,0 +1,826 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+ /* Toggle GPIO_LED pin 9 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_9, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_9)));
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+ /* Set the PSV system handler pending bit */
+ NVIC_SetSystemHandlerPendingBit(SystemHandler_PSV);
+
+ /* Toggle GPIO_LED pin 7 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_7, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_7)));
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+ /* Set the NMI system handler pending bit */
+ NVIC_SetSystemHandlerPendingBit(SystemHandler_NMI);
+
+ /* Toggle GPIO_LED pin 8 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_8, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_8)));
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+ __SVC();
+ /* Toggle GPIO_LED pin 6 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_6, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_6)));
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/System_Handlers/stm32f10x_it.h b/src/stm32lib/examples/NVIC/System_Handlers/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/NVIC/System_Handlers/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/EWARMv4/lnkarm_flash_offset.xcl b/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/EWARMv4/lnkarm_flash_offset.xcl new file mode 100755 index 0000000..fcb8787 --- /dev/null +++ b/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/EWARMv4/lnkarm_flash_offset.xcl @@ -0,0 +1,191 @@ +/*;******************** (C) COPYRIGHT 2008 STMicroelectronics ******************
+;* File Name : lnkarm_flash.xcl
+;* Author : MCD Application Team
+;* Version : V2.0.1
+;* Date : 06/13/2008
+;* Description : XLINK command file template for EWARM/ICCARM
+;* Usage : xlink -f lnkarm <your_object_file(s)>
+;* : -s <program start label> <C/C++ runtime library>
+;*******************************************************************************
+; 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.
+;******************************************************************************/
+
+// Code memory in FLASH
+-DROMSTART=0x8002000
+-DROMEND=0x807FFFF
+
+// Data in RAM
+-DRAMSTART=0x20000000
+-DRAMEND=0x2000FFFF
+
+//*************************************************************************
+// -------------
+// Code segments - may be placed anywhere in memory.
+// -------------
+//
+// INTVEC -- Exception vector table.
+// SWITAB -- Software interrupt vector table.
+// ICODE -- Startup (cstartup) and exception code.
+// DIFUNCT -- Dynamic initialization vectors used by C++.
+// CODE -- Compiler generated code.
+// CODE_I -- Compiler generated code declared __ramfunc (executes in RAM)
+// CODE_ID -- Initializer for CODE_I (ROM).
+//
+// -------------
+// Data segments - may be placed anywhere in memory.
+// -------------
+//
+// CSTACK -- The stack used by C/C++ programs (system and user mode).
+// HEAP -- The heap used by malloc and free in C and new and
+// delete in C++.
+// INITTAB -- Table containing addresses and sizes of segments that
+// need to be initialized at startup (by cstartup).
+// CHECKSUM -- The linker places checksum byte(s) in this segment,
+// when the -J linker command line option is used.
+// DATA_y -- Data objects.
+//
+// Where _y can be one of:
+//
+// _AN -- Holds uninitialized located objects, i.e. objects with
+// an absolute location given by the @ operator or the
+// #pragma location directive. Since these segments
+// contain objects which already have a fixed address,
+// they should not be mentioned in this linker command
+// file.
+// _C -- Constants (ROM).
+// _I -- Initialized data (RAM).
+// _ID -- The original content of _I (copied to _I by cstartup) (ROM).
+// _N -- Uninitialized data (RAM).
+// _Z -- Zero initialized data (RAM).
+//
+// Note: Be sure to use end values for the defined address ranges.
+// Otherwise, the linker may allocate space outside the
+// intended memory range.
+//*************************************************************************
+
+
+//************************************************
+// Inform the linker about the CPU family used.
+//************************************************
+
+-carm
+
+//*************************************************************************
+// Segment placement - General information
+//
+// All numbers in the segment placement command lines below are interpreted
+// as hexadecimal unless they are immediately preceded by a '.', which
+// denotes decimal notation.
+//
+// When specifying the segment placement using the -P instead of the -Z
+// option, the linker is free to split each segment into its segment parts
+// and randomly place these parts within the given ranges in order to
+// achieve a more efficient memory usage. One disadvantage, however, is
+// that it is not possible to find the start or end address (using
+// the assembler operators .sfb./.sfe.) of a segment which has been split
+// and reformed.
+//
+// When generating an output file which is to be used for programming
+// external ROM/Flash devices, the -M linker option is very useful
+// (see xlink.pdf for details).
+//*************************************************************************
+
+
+//*************************************************************************
+// Read-only segments mapped to ROM.
+//*************************************************************************
+
+//************************************************
+// Address range for reset and exception
+// vectors (INTVEC).
+//************************************************
+
+-Z(CODE)INTVEC=ROMSTART-ROMEND
+
+//************************************************
+// Startup code and exception routines (ICODE).
+//************************************************
+
+-Z(CODE)ICODE,DIFUNCT=ROMSTART-ROMEND
+-Z(CODE)SWITAB=ROMSTART-ROMEND
+
+//************************************************
+// Code segments may be placed anywhere.
+//************************************************
+
+-Z(CODE)CODE=ROMSTART-ROMEND
+
+//************************************************
+// Original ROM location for __ramfunc code copied
+// to and executed from RAM.
+//************************************************
+
+-Z(CONST)CODE_ID=ROMSTART-ROMEND
+
+//************************************************
+// Various constants and initializers.
+//************************************************
+
+-Z(CONST)INITTAB,DATA_ID,DATA_C=ROMSTART-ROMEND
+-Z(CONST)CHECKSUM=ROMSTART-ROMEND
+
+
+//*************************************************************************
+// Read/write segments mapped to RAM.
+//*************************************************************************
+
+//************************************************
+// Data segments.
+//************************************************
+
+-Z(DATA)DATA_I,DATA_Z,DATA_N=RAMSTART-RAMEND
+
+//************************************************
+// __ramfunc code copied to and executed from RAM.
+//************************************************
+
+-Z(DATA)CODE_I=RAMSTART-RAMEND
+
+//************************************************
+// ICCARM produces code for __ramfunc functions in
+// CODE_I segments. The -Q XLINK command line
+// option redirects XLINK to emit the code in the
+// CODE_ID segment instead, but to keep symbol and
+// debug information associated with the CODE_I
+// segment, where the code will execute.
+//************************************************
+
+-QCODE_I=CODE_ID
+
+//*************************************************************************
+// Stack and heap segments.
+//*************************************************************************
+
+-D_CSTACK_SIZE=400
+-D_HEAP_SIZE=200
+
+-Z(DATA)CSTACK+_CSTACK_SIZE=RAMSTART-RAMEND
+-Z(DATA)HEAP+_HEAP_SIZE=RAMSTART-RAMEND
+
+//*************************************************************************
+// ELF/DWARF support.
+//
+// Uncomment the line "-Felf" below to generate ELF/DWARF output.
+// Available format specifiers are:
+//
+// "-yn": Suppress DWARF debug output
+// "-yp": Multiple ELF program sections
+// "-yas": Format suitable for debuggers from ARM Ltd (also sets -p flag)
+//
+// "-Felf" and the format specifiers can also be supplied directly as
+// command line options, or selected from the Xlink Output tab in the
+// IAR Embedded Workbench.
+//*************************************************************************
+
+// -Felf
+
diff --git a/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/EWARMv5/stm32f10x_flash_offset.icf b/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/EWARMv5/stm32f10x_flash_offset.icf new file mode 100755 index 0000000..ac30a01 --- /dev/null +++ b/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/EWARMv5/stm32f10x_flash_offset.icf @@ -0,0 +1,31 @@ +/*###ICF### Section handled by ICF editor, don't touch! ****/
+/*-Editor annotation file-*/
+/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\a_v1_0.xml" */
+/*-Specials-*/
+define symbol __ICFEDIT_intvec_start__ = 0x08002000;
+/*-Memory Regions-*/
+define symbol __ICFEDIT_region_ROM_start__ = 0x08002000 ;
+define symbol __ICFEDIT_region_ROM_end__ = 0x0807FFFF;
+define symbol __ICFEDIT_region_RAM_start__ = 0x20000000;
+define symbol __ICFEDIT_region_RAM_end__ = 0x2000FFFF;
+/*-Sizes-*/
+define symbol __ICFEDIT_size_cstack__ = 0x400;
+define symbol __ICFEDIT_size_heap__ = 0x200;
+/**** End of ICF editor section. ###ICF###*/
+
+
+define memory mem with size = 4G;
+define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__];
+define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__];
+
+define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { };
+define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { };
+
+initialize by copy { readwrite };
+do not initialize { section .noinit };
+
+place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec };
+
+place in ROM_region { readonly };
+place in RAM_region { readwrite,
+ block CSTACK, block HEAP };
diff --git a/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/HiTOP/STM32F10x_offset.lsl b/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/HiTOP/STM32F10x_offset.lsl new file mode 100755 index 0000000..164cf72 --- /dev/null +++ b/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/HiTOP/STM32F10x_offset.lsl @@ -0,0 +1,132 @@ +// define rom size
+#define __ROM_SIZE 512k
+#define __ROM_ADDR 0x08002000
+// define ram size
+#define __RAM_SIZE 64k
+#define __RAM_ADDR 0x20000000
+
+#define __NR_OF_VECTORS 42
+#define __VECTOR_TABLE_SIZE (__NR_OF_VECTORS * 4)
+#define __VECTOR_TABLE_ROM_ADDR 0x08002000
+#define _Vectors 0x08002000
+
+#define _ENTRYADDR (0x08002001 + __VECTOR_TABLE_SIZE + 80) /* xB0 */
+
+#define _START max(_ENTRYADDR, 0x08002165)
+
+#define __RESET 0x08002004
+
+#define __STACK 0x400
+#define __STACKADDR (__RAM_ADDR + __RAM_SIZE - __STACK)
+#define __HEAP 2k
+
+#define __TABLE_RAM_SIZE 20
+#define __TABLE_RAM_ADDR (__STACKADDR - __STACK - __TABLE_RAM_SIZE)
+
+
+#define __MEMORY
+
+#define __PROCESSOR_MODE 0x10 /* User mode */
+#define __IRQ_BIT 0x80 /* IRQ interrupts disabled */
+#define __FIQ_BIT 0x40 /* FIQ interrupts disabled */
+#define __APPLICATION_MODE (__PROCESSOR_MODE | __IRQ_BIT | __FIQ_BIT)
+
+
+architecture ARM
+{
+ endianness
+ {
+ little;
+ big;
+ }
+ space linear
+ {
+ id = 1;
+ mau = 8;
+ align = 4;
+ map (size = 4G, dest = bus:local_bus);
+
+ copytable
+ (
+ align = 4,
+ copy_unit = 1,
+ dest = linear
+ );
+ start_address
+ (
+ // It is not strictly necessary to define a run_addr for _START
+ // because hardware starts execution at address 0x0 which should
+ // be the vector table with a jump to the relocatable _START, but
+ // an absolute address can prevent the branch to be out-of-range.
+ // Or _START may be the entry point at reset and the reset handler
+ // copies the vector table to address 0x0 after some ROM/RAM memory
+ // re-mapping. In that case _START should be at a fixed address
+ // in ROM, specifically the alias of address 0x0 before memory
+ // re-mapping.
+ run_addr = _START,
+ symbol = "_START"
+ );
+
+ stack "stack"
+ (
+
+ align = 4,
+ min_size = __STACK,
+ grows = high_to_low
+ );
+ heap "heap"
+ (
+ align = 4,
+ min_size=__HEAP
+ );
+ section_layout
+ {
+ "_lc_ub_vector_table" = __VECTOR_TABLE_ROM_ADDR;
+ "_lc_ue_vector_table" = __VECTOR_TABLE_ROM_ADDR + __VECTOR_TABLE_SIZE + 8;
+// "_lc_ub_table" = __TABLE_RAM_ADDR;
+// "_lc_ue_table" = __TABLE_RAM_ADDR + __TABLE_RAM_SIZE;
+ "_lc_ub_vector_table_copy" := "_lc_ub_vector_table";
+ "_lc_ue_vector_table_copy" := "_lc_ue_vector_table";
+
+ group ( ordered, run_addr=__VECTOR_TABLE_ROM_ADDR )
+ {
+ select ".text.vector";
+
+ }
+
+#ifdef __HEAPADDR
+ group ( ordered, run_addr=__HEAPADDR )
+ {
+ select "heap";
+ }
+#endif
+ group ( ordered, run_addr=__STACKADDR)
+ {
+ select "stack";
+ }
+ }
+ }
+ bus local_bus
+ {
+ mau = 8;
+ width = 32;
+ }
+}
+///////////////////////////////////////////////////////////////////
+
+
+memory flash
+{
+ mau = 8;
+ type = rom;
+ size = __ROM_SIZE;
+ map ( size = __ROM_SIZE, dest_offset = __ROM_ADDR, dest = bus:ARM:local_bus );
+}
+
+memory sram
+{
+ mau = 8;
+ type = ram;
+ size = __RAM_SIZE;
+ map ( size = __RAM_SIZE, dest_offset = __RAM_ADDR, dest = bus:ARM:local_bus );
+}
diff --git a/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/HiTOP/link_offset.lnk b/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/HiTOP/link_offset.lnk new file mode 100755 index 0000000..5bfdd21 --- /dev/null +++ b/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/HiTOP/link_offset.lnk @@ -0,0 +1,5 @@ +-d"./settings/STM32F10x_offset.lsl"
+--optimize=0
+--map-file-format=2
+$(LinkObjects)
+--output=.\Objects\$(Target)
\ No newline at end of file diff --git a/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/RIDE/stm32f10x_flash_offset.ld b/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/RIDE/stm32f10x_flash_offset.ld new file mode 100755 index 0000000..0fb109f --- /dev/null +++ b/src/stm32lib/examples/NVIC/VectorTable_Relocation/linker/RIDE/stm32f10x_flash_offset.ld @@ -0,0 +1,250 @@ +/*
+Default linker script for STM32F10x_512K_64K
+Copyright RAISONANCE S.A.S. 2008
+*/
+
+/* include the common STM32F10x sub-script */
+
+/* Common part of the linker scripts for STM32 devices*/
+
+
+/* default stack sizes.
+
+These are used by the startup in order to allocate stacks for the different modes.
+*/
+
+__Stack_Size = 1024 ;
+
+PROVIDE ( _Stack_Size = __Stack_Size ) ;
+
+__Stack_Init = _estack - __Stack_Size ;
+
+/*"PROVIDE" allows to easily override these values from an object file or the commmand line.*/
+PROVIDE ( _Stack_Init = __Stack_Init ) ;
+
+/*
+There will be a link error if there is not this amount of RAM free at the end.
+*/
+_Minimum_Stack_Size = 0x100 ;
+
+
+/* include the memory spaces definitions sub-script */
+/*
+Linker subscript for STM32F10x definitions with 512K Flash and 64K RAM */
+
+/* Memory Spaces Definitions */
+
+MEMORY
+{
+ RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 64K
+ FLASH (rx) : ORIGIN = 0x8002000, LENGTH = 512K-0x2000
+ FLASHB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+ EXTMEMB0 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+ EXTMEMB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+ EXTMEMB2 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+ EXTMEMB3 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+}
+
+/* higher address of the user mode stack */
+_estack = 0x20010000;
+
+
+
+/* include the sections management sub-script for FLASH mode */
+/*
+Common part of the linker scripts for STR71x devices in FLASH mode
+(that is, the FLASH is seen at 0)
+Copyright RAISONANCE 2005
+You can use, modify and distribute thisfile freely, but without any waranty.
+*/
+
+
+
+/* Sections Definitions */
+
+SECTIONS
+{
+ /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* for some STRx devices, the beginning of the startup code is stored in the .flashtext section, which goes to FLASH */
+ .flashtext :
+ {
+ . = ALIGN(4);
+ *(.flashtext) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+
+ /* the program code is stored in the .text section, which goes to Flash */
+ .text :
+ {
+ . = ALIGN(4);
+
+ *(.text) /* remaining code */
+ *(.text.*) /* remaining code */
+ *(.rodata) /* read-only data (constants) */
+ *(.rodata*)
+ *(.glue_7)
+ *(.glue_7t)
+
+ . = ALIGN(4);
+ _etext = .;
+ /* This is used by the startup in order to initialize the .data secion */
+ _sidata = _etext;
+ } >FLASH
+
+
+
+ /* This is the initialized data section
+ The program executes knowing that the data is in the RAM
+ but the loader puts the initial values in the FLASH (inidata).
+ It is one task of the startup to copy the initial values from FLASH to RAM. */
+ .data : AT ( _sidata )
+ {
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .data secion */
+ _sdata = . ;
+
+ *(.data)
+ *(.data.*)
+
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .data secion */
+ _edata = . ;
+ } >RAM
+
+
+
+ /* This is the uninitialized data section */
+ .bss :
+ {
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .bss secion */
+ _sbss = .;
+
+ *(.bss)
+ *(COMMON)
+
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .bss secion */
+ _ebss = . ;
+ } >RAM
+
+ PROVIDE ( end = _ebss );
+ PROVIDE ( _end = _ebss );
+
+ /* This is the user stack section
+ This is just to check that there is enough RAM left for the User mode stack
+ It should generate an error if it's full.
+ */
+ ._usrstack :
+ {
+ . = ALIGN(4);
+ _susrstack = . ;
+
+ . = . + _Minimum_Stack_Size ;
+
+ . = ALIGN(4);
+ _eusrstack = . ;
+ } >RAM
+
+
+
+ /* this is the FLASH Bank1 */
+ /* the C or assembly source must explicitly place the code or data there
+ using the "section" attribute */
+ .b1text :
+ {
+ *(.b1text) /* remaining code */
+ *(.b1rodata) /* read-only data (constants) */
+ *(.b1rodata*)
+ } >FLASHB1
+
+ /* this is the EXTMEM */
+ /* the C or assembly source must explicitly place the code or data there
+ using the "section" attribute */
+
+ /* EXTMEM Bank0 */
+ .eb0text :
+ {
+ *(.eb0text) /* remaining code */
+ *(.eb0rodata) /* read-only data (constants) */
+ *(.eb0rodata*)
+ } >EXTMEMB0
+
+ /* EXTMEM Bank1 */
+ .eb1text :
+ {
+ *(.eb1text) /* remaining code */
+ *(.eb1rodata) /* read-only data (constants) */
+ *(.eb1rodata*)
+ } >EXTMEMB1
+
+ /* EXTMEM Bank2 */
+ .eb2text :
+ {
+ *(.eb2text) /* remaining code */
+ *(.eb2rodata) /* read-only data (constants) */
+ *(.eb2rodata*)
+ } >EXTMEMB2
+
+ /* EXTMEM Bank0 */
+ .eb3text :
+ {
+ *(.eb3text) /* remaining code */
+ *(.eb3rodata) /* read-only data (constants) */
+ *(.eb3rodata*)
+ } >EXTMEMB3
+
+
+
+ /* after that it's only debugging information. */
+
+ /* remove the debugging information from the standard libraries */
+ DISCARD :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ /* DWARF debug sections.
+ Symbols in the DWARF debugging sections are relative to the beginning
+ of the section so we begin them at 0. */
+ /* DWARF 1 */
+ .debug 0 : { *(.debug) }
+ .line 0 : { *(.line) }
+ /* GNU DWARF 1 extensions */
+ .debug_srcinfo 0 : { *(.debug_srcinfo) }
+ .debug_sfnames 0 : { *(.debug_sfnames) }
+ /* DWARF 1.1 and DWARF 2 */
+ .debug_aranges 0 : { *(.debug_aranges) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ /* DWARF 2 */
+ .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_frame 0 : { *(.debug_frame) }
+ .debug_str 0 : { *(.debug_str) }
+ .debug_loc 0 : { *(.debug_loc) }
+ .debug_macinfo 0 : { *(.debug_macinfo) }
+ /* SGI/MIPS DWARF 2 extensions */
+ .debug_weaknames 0 : { *(.debug_weaknames) }
+ .debug_funcnames 0 : { *(.debug_funcnames) }
+ .debug_typenames 0 : { *(.debug_typenames) }
+ .debug_varnames 0 : { *(.debug_varnames) }
+}
diff --git a/src/stm32lib/examples/NVIC/VectorTable_Relocation/main.c b/src/stm32lib/examples/NVIC/VectorTable_Relocation/main.c new file mode 100755 index 0000000..bc22e81 --- /dev/null +++ b/src/stm32lib/examples/NVIC/VectorTable_Relocation/main.c @@ -0,0 +1,216 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+GPIO_InitTypeDef GPIO_InitStructure;
+static vu32 TimingDelay;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+void Delay(vu32 nTime);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* Configure GPIO_LED pin 6, pin 7, pin 8 and pin 9 as Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ /* Turn on Leds connected to GPIO_LED pin 6 and pin 8 */
+ GPIO_Write(GPIO_LED, GPIO_Pin_6 | GPIO_Pin_8);
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* SysTick end of count event each 1ms with input clock equal to 9MHz (HCLK/8, default) */
+ SysTick_SetReload(9000);
+
+ /* Enable SysTick interrupt */
+ SysTick_ITConfig(ENABLE);
+
+ while (1)
+ {
+ /* Toggle leds connected to GPIO_LED pin 6, GPIO_LED pin 7, GPIO_LED pin 8
+ and GPIO_LED pin 9 pins */
+ GPIO_Write(GPIO_LED, (u16)~GPIO_ReadOutputData(GPIO_LED));
+
+ /* Insert 500 ms delay */
+ Delay(500);
+
+ /* Toggle leds connected to GPIO_LED pin 6, pin 7, pin 8 and pin 9 */
+ GPIO_Write(GPIO_LED, (u16)~GPIO_ReadOutputData(GPIO_LED));
+
+ /* Insert 300 ms delay */
+ Delay(300);
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable GPIO_LED clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_LED, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ /* Set the Vector Table base location at 0x08002000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x2000);
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nTime: specifies the delay time length, in milliseconds.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(u32 nTime)
+{
+ /* Enable the SysTick Counter */
+ SysTick_CounterCmd(SysTick_Counter_Enable);
+
+ TimingDelay = nTime;
+
+ while(TimingDelay != 0);
+
+ /* Disable SysTick Counter */
+ SysTick_CounterCmd(SysTick_Counter_Disable);
+ /* Clear SysTick Counter */
+ SysTick_CounterCmd(SysTick_Counter_Clear);
+}
+
+/*******************************************************************************
+* Function Name : TimingDelay_Decrement
+* Description : Decrements the TimingDelay variable.
+* Input : None
+* Output : TimingDelay
+* Return : None
+*******************************************************************************/
+void TimingDelay_Decrement(void)
+{
+ if (TimingDelay != 0x00)
+ {
+ TimingDelay--;
+ }
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/VectorTable_Relocation/main.h b/src/stm32lib/examples/NVIC/VectorTable_Relocation/main.h new file mode 100755 index 0000000..feefea5 --- /dev/null +++ b/src/stm32lib/examples/NVIC/VectorTable_Relocation/main.h @@ -0,0 +1,32 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Header for main.c module
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __MAIN_H
+#define __MAIN_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void TimingDelay_Decrement(void);
+
+#endif /* __MAIN_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/VectorTable_Relocation/platform_config.h b/src/stm32lib/examples/NVIC/VectorTable_Relocation/platform_config.h new file mode 100755 index 0000000..0bc5169 --- /dev/null +++ b/src/stm32lib/examples/NVIC/VectorTable_Relocation/platform_config.h @@ -0,0 +1,44 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/VectorTable_Relocation/readme.txt b/src/stm32lib/examples/NVIC/VectorTable_Relocation/readme.txt new file mode 100755 index 0000000..f9aec02 --- /dev/null +++ b/src/stm32lib/examples/NVIC/VectorTable_Relocation/readme.txt @@ -0,0 +1,131 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the NVIC VectorTable_Relocation Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example describes how to use the NVIC firmware library to set the CortexM3
+vector table in a specific address other than default.
+
+This can be used to build program which will be loaded into Flash memory by an
+application previously programmed from the Flash memory base address.
+Such application can be In-Application Programming (IAP, through USART) or
+Device Firmware Upgrade (DFU, through USB).
+These applications are available for download from the ST microcontrollers
+website: www.st.com/stm32
+
+The associated program implements a "Delay" function based on SysTick end of count
+interrupt, and toggles four leds with timing defined by the "Delay" function.
+
+When using the IAP to load your porgram, the vector table must be relocated at
+address 0x08002000.
+When using the DFU to load your porgram, the vector table must be relocated at
+address 0x08003000.
+
+
+Directory contents
+==================
+ + \linker
+ + \EWARMv4
+ + lnkarm_flash_offset.xcl XLINK command file template for EWARM4
+ + \EWARMv5
+ + stm32f10x_flash_offset.icf ILINK command file template for EWARM5
+ + \RIDE
+ + stm32f10x_flash.ld linker script for RIDE
+ + \HiTOP
+ + STM32F10x_offset.lsl linker file for HiTOP
+ + link_offset script for HiTOP
+
+ + platform_config.h Evaluation board specific configuration file
+ + stm32f10x_conf.h Library Configuration file
+ + stm32f10x_it.c Interrupt handlers
+ + stm32f10x_it.h Interrupt handlers header file
+ + main.c Main program
+ + main.h Header for main.c
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PC.06, PC.07, PC.08
+ and PC.09 pins
+
+ + STM3210E-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PF.06, PF0.7, PF.08
+ and PF.09 pins
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files:
+ + RVMDK
+ - in the project option menu, select 'Target' window and enter 0x08002000
+ as IROM start address
+ - in the project option menu, select 'Linker' window and enter 0x08002000
+ as R/O base address
+
+ + EWARM4
+ - use "lnkarm_flash_offset.xcl" as linker file
+
+ + EWARM5
+ - use "stm32f10x_flash_offset.icf" as linker file
+
+ + RIDE
+ - In the Application options -> script menu, set "Use Default Script File"
+ to "No" and use "stm32f10x_flash_offset.ld" as Script File.
+ This linker is configured for STM32 High-density devices. To use it with
+ Medium-density devices, this linker should be updated as follows:
+ - line39: RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K
+ - line40: FLASH (rx) : ORIGIN = 0x8002000, LENGTH = 128K-0x2000
+ - line49: _estack = 0x20005000;
+
+ + HiTOP
+ - copy the "link_offset" and "STM32F10x_offset.lsl" files under "Settings"
+ folder which is created by default by HiTOP.
+ - in project->settings->project->tool settings ->linker,
+ use "link_offset.lnk" as linker file.
+ This linker is configured for STM32 High-density devices. To use it with
+ Medium-density devices, this linker should be updated as follows:
+ - line2: #define __ROM_SIZE 128k
+ - line5: #define __RAM_SIZE 20k
+
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_systick.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- In the main.c and linker files, the vector table is relocated at address 0x08002000.
+ You can modify this address depending on the requirement of your application.
+
+- Rebuild all files
+
+- Convert the program image to a binary file, *.bin, then you can download and
+ run it using the IAP or DFU application.
+
+NOTE:
+ - Medium-density devices are STM32F101xx and STM32F103xx microcontrollers where
+ the Flash memory density ranges between 32 and 128 Kbytes.
+ - High-density devices are STM32F101xx and STM32F103xx microcontrollers where
+ the Flash memory density ranges between 256 and 512 Kbytes.
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/NVIC/VectorTable_Relocation/stm32f10x_conf.h b/src/stm32lib/examples/NVIC/VectorTable_Relocation/stm32f10x_conf.h new file mode 100755 index 0000000..f421f9a --- /dev/null +++ b/src/stm32lib/examples/NVIC/VectorTable_Relocation/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/VectorTable_Relocation/stm32f10x_it.c b/src/stm32lib/examples/NVIC/VectorTable_Relocation/stm32f10x_it.c new file mode 100755 index 0000000..3f1d5aa --- /dev/null +++ b/src/stm32lib/examples/NVIC/VectorTable_Relocation/stm32f10x_it.c @@ -0,0 +1,812 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "main.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+ TimingDelay_Decrement();
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/NVIC/VectorTable_Relocation/stm32f10x_it.h b/src/stm32lib/examples/NVIC/VectorTable_Relocation/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/NVIC/VectorTable_Relocation/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/PWR/STANDBY/main.c b/src/stm32lib/examples/PWR/STANDBY/main.c new file mode 100755 index 0000000..a4fbc16 --- /dev/null +++ b/src/stm32lib/examples/PWR/STANDBY/main.c @@ -0,0 +1,311 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void EXTI_Configuration(void);
+void RTC_Configuration(void);
+void NVIC_Configuration(void);
+void SysTick_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* GPIO configuration */
+ GPIO_Configuration();
+
+ /* Turn on led connected to GPIO_LED Pin6 */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_6);
+
+ /* Enable PWR and BKP clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE);
+
+ /* Enable WKUP pin */
+ PWR_WakeUpPinCmd(ENABLE);
+
+ /* Allow access to BKP Domain */
+ PWR_BackupAccessCmd(ENABLE);
+
+ /* Configure RTC clock source and prescaler */
+ RTC_Configuration();
+
+ /* Configure EXTI Line to generate an interrupt on falling edge */
+ EXTI_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the SysTick to generate an interrupt each 250 ms */
+ SysTick_Configuration();
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Enable Key Button GPIO Port, GPIO_LED and AFIO clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_KEY_BUTTON | RCC_APB2Periph_GPIO_LED
+ | RCC_APB2Periph_AFIO, ENABLE);
+
+ /* Configure GPIO_LED Pin 6 and Pin 7 as Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ /* Configure Key Button GPIO Pin as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_KEY_BUTTON;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIO_KEY_BUTTON, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : EXTI_Configuration
+* Description : Configures EXTI Line.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_Configuration(void)
+{
+ EXTI_InitTypeDef EXTI_InitStructure;
+
+ /* Connect Key Button EXTI Line to Key Button GPIO Pin */
+ GPIO_EXTILineConfig(GPIO_PORT_SOURCE_KEY_BUTTON, GPIO_PIN_SOURCE_KEY_BUTTON);
+
+ /* Configure Key Button EXTI Line to generate an interrupt on falling edge */
+ EXTI_InitStructure.EXTI_Line = EXTI_LINE_KEY_BUTTON;
+ EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
+ EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+ EXTI_Init(&EXTI_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : RTC_Configuration
+* Description : Configures RTC clock source and prescaler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_Configuration(void)
+{
+ /* Check if the StandBy flag is set */
+ if(PWR_GetFlagStatus(PWR_FLAG_SB) != RESET)
+ {/* System resumed from STANDBY mode */
+
+ /* Turn on led connected to GPIO_LED Pin7 */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_7);
+
+ /* Clear StandBy flag */
+ PWR_ClearFlag(PWR_FLAG_SB);
+
+ /* Wait for RTC APB registers synchronisation */
+ RTC_WaitForSynchro();
+ /* No need to configure the RTC as the RTC configuration(clock source, enable,
+ prescaler,...) is kept after wake-up from STANDBY */
+ }
+ else
+ {/* StandBy flag is not set */
+
+ /* RTC clock source configuration ----------------------------------------*/
+ /* Reset Backup Domain */
+ BKP_DeInit();
+
+ /* Enable LSE OSC */
+ RCC_LSEConfig(RCC_LSE_ON);
+ /* Wait till LSE is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_LSERDY) == RESET)
+ {
+ }
+
+ /* Select the RTC Clock Source */
+ RCC_RTCCLKConfig(RCC_RTCCLKSource_LSE);
+
+ /* Enable the RTC Clock */
+ RCC_RTCCLKCmd(ENABLE);
+
+ /* RTC configuration -----------------------------------------------------*/
+ /* Wait for RTC APB registers synchronisation */
+ RTC_WaitForSynchro();
+
+ /* Set the RTC time base to 1s */
+ RTC_SetPrescaler(32767);
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures NVIC and Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+
+ NVIC_InitStructure.NVIC_IRQChannel = EXTI9_5_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : SysTick_Configuration
+* Description : Configures the SysTick to generate an interrupt each 250 ms.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTick_Configuration(void)
+{
+ /* Select AHB clock(HCLK) divided by 8 as SysTick clock source */
+ SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK_Div8);
+
+ /* Set SysTick Preemption Priority to 1 */
+ NVIC_SystemHandlerPriorityConfig(SystemHandler_SysTick, 1, 0);
+
+ /* SysTick interrupt each 250 ms with HCLK equal to 9MHz */
+ SysTick_SetReload(2250000);
+
+ /* Enable the SysTick Interrupt */
+ SysTick_ITConfig(ENABLE);
+
+ /* Enable the SysTick Counter */
+ SysTick_CounterCmd(SysTick_Counter_Enable);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/PWR/STANDBY/platform_config.h b/src/stm32lib/examples/PWR/STANDBY/platform_config.h new file mode 100755 index 0000000..3deb7ba --- /dev/null +++ b/src/stm32lib/examples/PWR/STANDBY/platform_config.h @@ -0,0 +1,56 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+ #define GPIO_KEY_BUTTON GPIOB
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOB
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_9
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line9
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOB
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource9
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+ #define GPIO_KEY_BUTTON GPIOG
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOG
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_8
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line8
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOG
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource8
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/PWR/STANDBY/readme.txt b/src/stm32lib/examples/PWR/STANDBY/readme.txt new file mode 100755 index 0000000..242129f --- /dev/null +++ b/src/stm32lib/examples/PWR/STANDBY/readme.txt @@ -0,0 +1,97 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the PWR STANDBY Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to enters the system to STANDBY mode and wake-up from this
+mode using: external RESET, RTC Alarm or WKUP pin.
+
+In the associated software, the system clock is set to 72 MHz, an EXTI line
+is configured to generate an interrupt on falling edge and the SysTick is programmed
+to generate an interrupt each 250 ms. In the SysTick interrupt handler, a led
+connected to GPIO_LED Pin6(LD1) is toggled, this is used to indicate whether the MCU is
+in STANDBY or RUN mode.
+When a falling edge is detected on the EXTI line an interrupt is generated. In the
+EXTI handler routine the RTC is configured to generate an Alarm event in 3 second
+then the system enters STANDBY mode causing the LD1 to stop toggling.
+A rising edge on WKUP pin or an external RESET will wake-up the system from
+STANDBY. If within 3 second neither rising edge on WKUP pin nor external RESET
+are generated, the RTC Alarm will wake-up the system.
+After wake-up from STANDBY mode, program execution restarts in the same way as after
+a RESET, the LD1 restarts toggling, GPIO_LED Pin6 is set to high level and the RTC
+configuration (clock source, enable, prescaler,...) is kept. As result there is no
+need to configure the RTC.
+
+Two leds connected to GPIO_LED Pin6(LD1) and Pin7(LD2) pins are used to monitor
+the system state as following:
+ - LD1 toggling: system in RUN mode
+ - LD1 off / LD2 off: system in STANDBY mode
+ - LD2 on: system resumed from STANDBY mode
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+main.h Header for main.c
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1 and LD2 leds connected respectively to PC.06 and PC.07 pins
+ - Use the Key push-button connected to pin PB.09 (EXTI Line9).
+ - Use the Wakep push-button connected to WKUP(PA.00) pin
+
+ + STM3210E-EVAL
+ - Use LD1 and LD2 leds connected respectively to PF.06 and PF.07 pins
+ - Use the Key push-button connected to pin PG.08 (EXTI Line8).
+ - Use the Wakep push-button connected to WKUP(PA.00) pin
+ Note: the jumper JP4 must be not fit to be able to use the Wakeup push-button
+
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_nvic.c
+ + stm32f10x_rcc.c
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rtc.c
+ + stm32f10x_pwr.c
+ + stm32f10x_bkp.c
+ + stm32f10x_exti.c
+ + stm32f10x_flash.c
+ + stm32f10x_systick.c
+- Link all compiled files and load your image into target memory
+- Run the example in standalone mode (without debugger connection)
+
+NOTE: For power consumption measurement in STANDBY mode, you have to replace
+ jumper JP9 in the STM3210B-EVAL board or JP12 in the STM3210E-EVAL board
+ by an ampermeter.
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/PWR/STANDBY/stm32f10x_conf.h b/src/stm32lib/examples/PWR/STANDBY/stm32f10x_conf.h new file mode 100755 index 0000000..0838006 --- /dev/null +++ b/src/stm32lib/examples/PWR/STANDBY/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+#define _GPIOD
+#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/PWR/STANDBY/stm32f10x_it.c b/src/stm32lib/examples/PWR/STANDBY/stm32f10x_it.c new file mode 100755 index 0000000..ba46a35 --- /dev/null +++ b/src/stm32lib/examples/PWR/STANDBY/stm32f10x_it.c @@ -0,0 +1,833 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+ /* Toggle Led connected to GPIO_LED Pin6 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_6, (BitAction)(1-GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_6)));
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+ if(EXTI_GetITStatus(EXTI_LINE_KEY_BUTTON) != RESET)
+ {
+ /* Clear the Key Button EXTI line pending bit */
+ EXTI_ClearITPendingBit(EXTI_LINE_KEY_BUTTON);
+
+ /* Turn on led connected to GPIO_LED pin6 */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_6);
+
+ /* Wait till RTC Second event occurs */
+ RTC_ClearFlag(RTC_FLAG_SEC);
+ while(RTC_GetFlagStatus(RTC_FLAG_SEC) == RESET);
+
+ /* Set the RTC Alarm after 3s */
+ RTC_SetAlarm(RTC_GetCounter()+ 3);
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+
+ /* Request to enter STANDBY mode (Wake Up flag is cleared in PWR_EnterSTANDBYMode function) */
+ PWR_EnterSTANDBYMode();
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/PWR/STANDBY/stm32f10x_it.h b/src/stm32lib/examples/PWR/STANDBY/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/PWR/STANDBY/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/PWR/STOP/main.c b/src/stm32lib/examples/PWR/STOP/main.c new file mode 100755 index 0000000..48e715e --- /dev/null +++ b/src/stm32lib/examples/PWR/STOP/main.c @@ -0,0 +1,391 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+extern vu32 TimingDelay;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void SYSCLKConfig_STOP(void);
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void EXTI_Configuration(void);
+void RTC_Configuration(void);
+void NVIC_Configuration(void);
+void SysTick_Configuration(void);
+void Delay(vu32 nTime);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* Clock configuration */
+ RCC_Configuration();
+
+ /* Enable PWR and BKP clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE);
+
+ /* GPIO configuration */
+ GPIO_Configuration();
+
+ /* Configure EXTI Line to generate an interrupt on falling edge */
+ EXTI_Configuration();
+
+ /* Configure RTC clock source and prescaler */
+ RTC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the SysTick to generate an interrupt each 1 millisecond */
+ SysTick_Configuration();
+
+ /* Turn on led connected to GPIO_LED Pin6 */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_6);
+
+ while (1)
+ {
+ /* Insert 1.5 second delay */
+ Delay(1500);
+
+ /* Wait till RTC Second event occurs */
+ RTC_ClearFlag(RTC_FLAG_SEC);
+ while(RTC_GetFlagStatus(RTC_FLAG_SEC) == RESET);
+
+ /* Alarm in 3 second */
+ RTC_SetAlarm(RTC_GetCounter()+ 3);
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+
+ /* Turn off led connected to GPIO_LED Pin6 */
+ GPIO_ResetBits(GPIO_LED, GPIO_Pin_6);
+
+ /* Request to enter STOP mode with regulator in low power mode*/
+ PWR_EnterSTOPMode(PWR_Regulator_LowPower, PWR_STOPEntry_WFI);
+
+ /* At this stage the system has resumed from STOP mode -------------------*/
+ /* Turn on led connected to GPIO_LED Pin6 */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_6);
+
+ /* Configures system clock after wake-up from STOP: enable HSE, PLL and select
+ PLL as system clock source (HSE and PLL are disabled in STOP mode) */
+ SYSCLKConfig_STOP();
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------------------------*/
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : SYSCLKConfig_STOP
+* Description : Configures system clock after wake-up from STOP: enable HSE, PLL
+* and select PLL as system clock source.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SYSCLKConfig_STOP(void)
+{
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Enable Key Button GPIO Port, GPIO_LED and AFIO clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_KEY_BUTTON | RCC_APB2Periph_GPIO_LED
+ | RCC_APB2Periph_AFIO, ENABLE);
+
+ /* Configure GPIO_LED Pin 6, Pin 7 and Pin 8 as Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ /* Configure Key Button GPIO Pin as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_KEY_BUTTON;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIO_KEY_BUTTON, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : EXTI_Configuration
+* Description : Configures EXTI Lines.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_Configuration(void)
+{
+ EXTI_InitTypeDef EXTI_InitStructure;
+
+ /* Connect Key Button EXTI Line to Key Button GPIO Pin */
+ GPIO_EXTILineConfig(GPIO_PORT_SOURCE_KEY_BUTTON, GPIO_PIN_SOURCE_KEY_BUTTON);
+
+ /* Configure Key Button EXTI Line to generate an interrupt on falling edge */
+ EXTI_InitStructure.EXTI_Line = EXTI_LINE_KEY_BUTTON;
+ EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
+ EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+ EXTI_Init(&EXTI_InitStructure);
+
+ /* Configure EXTI Line17(RTC Alarm) to generate an interrupt on rising edge */
+ EXTI_ClearITPendingBit(EXTI_Line17);
+ EXTI_InitStructure.EXTI_Line = EXTI_Line17;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
+ EXTI_Init(&EXTI_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : RTC_Configuration
+* Description : Configures RTC clock source and prescaler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_Configuration(void)
+{
+ /* RTC clock source configuration ------------------------------------------*/
+ /* Allow access to BKP Domain */
+ PWR_BackupAccessCmd(ENABLE);
+
+ /* Reset Backup Domain */
+ BKP_DeInit();
+
+ /* Enable the LSE OSC */
+ RCC_LSEConfig(RCC_LSE_ON);
+ /* Wait till LSE is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_LSERDY) == RESET)
+ {
+ }
+
+ /* Select the RTC Clock Source */
+ RCC_RTCCLKConfig(RCC_RTCCLKSource_LSE);
+
+ /* Enable the RTC Clock */
+ RCC_RTCCLKCmd(ENABLE);
+
+ /* RTC configuration -------------------------------------------------------*/
+ /* Wait for RTC APB registers synchronisation */
+ RTC_WaitForSynchro();
+
+ /* Set the RTC time base to 1s */
+ RTC_SetPrescaler(32767);
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+
+ /* Enable the RTC Alarm interrupt */
+ RTC_ITConfig(RTC_IT_ALR, ENABLE);
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures NVIC and Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+
+ /* 2 bits for Preemption Priority and 2 bits for Sub Priority */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
+
+ NVIC_InitStructure.NVIC_IRQChannel = RTCAlarm_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ NVIC_InitStructure.NVIC_IRQChannel = EXTI9_5_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : SysTick_Configuration
+* Description : Configures the SysTick to generate an interrupt each 1 millisecond.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTick_Configuration(void)
+{
+ /* Select AHB clock(HCLK) as SysTick clock source */
+ SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK);
+
+ /* Set SysTick Priority to 3 */
+ NVIC_SystemHandlerPriorityConfig(SystemHandler_SysTick, 3, 0);
+
+ /* SysTick interrupt each 1ms with HCLK equal to 72MHz */
+ SysTick_SetReload(72000);
+
+ /* Enable the SysTick Interrupt */
+ SysTick_ITConfig(ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nTime: specifies the delay time length, in milliseconds.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(u32 nTime)
+{
+ /* Enable the SysTick Counter */
+ SysTick_CounterCmd(SysTick_Counter_Enable);
+
+ TimingDelay = nTime;
+
+ while(TimingDelay != 0);
+
+ /* Disable the SysTick Counter */
+ SysTick_CounterCmd(SysTick_Counter_Disable);
+ /* Clear the SysTick Counter */
+ SysTick_CounterCmd(SysTick_Counter_Clear);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/PWR/STOP/platform_config.h b/src/stm32lib/examples/PWR/STOP/platform_config.h new file mode 100755 index 0000000..3deb7ba --- /dev/null +++ b/src/stm32lib/examples/PWR/STOP/platform_config.h @@ -0,0 +1,56 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+ #define GPIO_KEY_BUTTON GPIOB
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOB
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_9
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line9
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOB
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource9
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+ #define GPIO_KEY_BUTTON GPIOG
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOG
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_8
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line8
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOG
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource8
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/PWR/STOP/readme.txt b/src/stm32lib/examples/PWR/STOP/readme.txt new file mode 100755 index 0000000..fa6bbb3 --- /dev/null +++ b/src/stm32lib/examples/PWR/STOP/readme.txt @@ -0,0 +1,95 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the PWR STOP Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to enter the system to STOP mode and wake-up using EXTI
+Line interrupts. The EXTI Line sources are PB.09/PG.08 and RTC Alarm.
+
+The EXTI line9/8 is configured to generate interrupt on falling edge.
+The EXTI line17(RTC Alarm) is configured to generate interrupt on rising edge and
+the RTC time base is set to 1 second using the external low speed oscillator(LSE).
+
+The system clock is set to 72 MHz using the external high speed oscillator(HSE).
+
+The system enters and exits STOP mode as following:
+After 2 second from system start-up, the RTC is configured to generate an Alarm
+event in 3 second then the system enters STOP mode. To wake-up from STOP mode you
+have to apply a rising edge on EXTI line9/8, otherwise the RTC Alarm will wake-up
+the system within 3 second. After exit from STOP the system clock is reconfigured
+to its previous state (as HSE and PLL are disabled in STOP mode).
+Then after a delay the system will enter again in STOP mode and exit in the way
+described above. This behavior is repeated in an infinite loop.
+
+Four leds connected to GPIO_LED Pin6(LD1), Pin7(LD2) and Pin8(LD3) are used to
+monitor the system state as following:
+ - LD1 on: system in RUN mode
+ - LD1 off: system in STOP mode
+ - LD2 is toggled if EXTI Line9/8 is used to exit from STOP
+ - LD3 is toggled if EXTI line17(RTC Alarm) is used to exit from STOP
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+main.h Header for main.c
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1, LD2 and LD3 leds connected respectively to PC.06, PC.07 and PC.08 pins
+ - Use the Key push-button connected to pin PB.09 (EXTI Line9).
+
+ + STM3210E-EVAL
+ - Use LD1, LD2 and LD3 leds connected respectively to PF.06, PF0.7 and PF.08 pins
+ - Use the Key push-button connected to pin PG.08 (EXTI Line8).
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_nvic.c
+ + stm32f10x_rcc.c
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rtc.c
+ + stm32f10x_pwr.c
+ + stm32f10x_bkp.c
+ + stm32f10x_exti.c
+ + stm32f10x_flash.c
+ + stm32f10x_systick.c
+
+- Link all compiled files and load your image into target memory
+- Run the example in standalone mode (without debugger connection)
+
+NOTE: For power consumption measurement in STOP mode you have to:
+1. Modify the example to configure all unused GPIO port pins in Analog Input mode
+ (floating input trigger OFF). Refer to GPIO\IOToggle example for more details.
+2. Replace jumper JP9 in the STM3210B-EVAL board or JP12 in the STM3210E-EVAL
+ board by an ampermeter.
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/PWR/STOP/stm32f10x_conf.h b/src/stm32lib/examples/PWR/STOP/stm32f10x_conf.h new file mode 100755 index 0000000..0838006 --- /dev/null +++ b/src/stm32lib/examples/PWR/STOP/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+#define _GPIOD
+#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/PWR/STOP/stm32f10x_it.c b/src/stm32lib/examples/PWR/STOP/stm32f10x_it.c new file mode 100755 index 0000000..9cebedd --- /dev/null +++ b/src/stm32lib/examples/PWR/STOP/stm32f10x_it.c @@ -0,0 +1,844 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+vu32 TimingDelay = 0;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+ TimingDelay--;
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+ if(EXTI_GetITStatus(EXTI_LINE_KEY_BUTTON) != RESET)
+ {
+ /* Clear the Key Button EXTI line pending bit */
+ EXTI_ClearITPendingBit(EXTI_LINE_KEY_BUTTON);
+
+ /* Toggle Led connected to GPIO_LED pin7 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_7, (BitAction)(1-GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_7)));
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+ if(RTC_GetITStatus(RTC_IT_ALR) != RESET)
+ {
+ /* Toggle Led connected to GPIO_LED Pin8 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_8, (BitAction)(1-GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_8)));
+
+ /* Clear EXTI line17 pending bit */
+ EXTI_ClearITPendingBit(EXTI_Line17);
+
+ /* Check if the Wake-Up flag is set */
+ if(PWR_GetFlagStatus(PWR_FLAG_WU) != RESET)
+ {
+ /* Clear Wake Up flag */
+ PWR_ClearFlag(PWR_FLAG_WU);
+ }
+
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+ /* Clear RTC Alarm interrupt pending bit */
+ RTC_ClearITPendingBit(RTC_IT_ALR);
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+ }
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/PWR/STOP/stm32f10x_it.h b/src/stm32lib/examples/PWR/STOP/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/PWR/STOP/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RCC/main.c b/src/stm32lib/examples/RCC/main.c new file mode 100755 index 0000000..59ccf7d --- /dev/null +++ b/src/stm32lib/examples/RCC/main.c @@ -0,0 +1,507 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define DELAY_COUNT 0xFFFFF
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+GPIO_InitTypeDef GPIO_InitStructure;
+RCC_ClocksTypeDef RCC_ClockFreq;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void SetSysClock(void);
+void SetSysClockToHSE(void);
+void SetSysClockTo20(void);
+void SetSysClockTo36(void);
+void SetSysClockTo48(void);
+void SetSysClockTo72(void);
+void NVIC_Configuration(void);
+void Delay(vu32 nCount);
+
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers */
+ SetSysClock();
+
+ /* This function fills the RCC_ClockFreq structure with the current
+ frequencies of different on chip clocks (for debug purpose) */
+ RCC_GetClocksFreq(&RCC_ClockFreq);
+
+ /* Enable Clock Security System(CSS): this will generate an NMI exception
+ when HSE clock fails */
+ RCC_ClockSecuritySystemCmd(ENABLE);
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* Enable GPIO_LED and GPIOA clock -----------------------------------------*/
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_LED | RCC_APB2Periph_GPIOA, ENABLE);
+
+ /* Configure GPIO_LED Pin 6, Pin 7, Pin 8 and Pin 9 as Output push-pull ----*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ /* Turn on Leds connected to GPIO_LED Pin 7 and Pin 9 */
+ GPIO_Write(GPIO_LED, GPIO_Pin_7 | GPIO_Pin_9);
+
+ /* Output HSE clock on MCO pin */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+ RCC_MCOConfig(RCC_MCO_HSE);
+
+ /* Toggle leds connected to GPIO_LED Pin 6, Pin 7, Pin 8 and Pin 9 pins */
+ while (1)
+ {
+ GPIO_Write(GPIO_LED, (u16)~GPIO_ReadOutputData(GPIO_LED));
+
+ /* Insert a delay */
+ Delay(DELAY_COUNT);
+ }
+}
+
+/*******************************************************************************
+* Function Name : SetSysClock
+* Description : Configures the System clock frequency, HCLK, PCLK2 and PCLK1
+* prescalers.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SetSysClock(void)
+{
+#if defined SYSCLK_HSE
+ SetSysClockToHSE();
+#elif defined SYSCLK_FREQ_20MHz
+ SetSysClockTo20();
+#elif defined SYSCLK_FREQ_36MHz
+ SetSysClockTo36();
+#elif defined SYSCLK_FREQ_48MHz
+ SetSysClockTo48();
+#elif defined SYSCLK_FREQ_72MHz
+ SetSysClockTo72();
+#endif
+
+ /* If none of the define above is enabled, the HSI is used as System clock
+ source (default after reset) */
+}
+
+/*******************************************************************************
+* Function Name : SetSysClockToHSE
+* Description : Selects HSE as System clock source and configure HCLK, PCLK2
+* and PCLK1 prescalers.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SetSysClockToHSE(void)
+{
+ /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------------------------*/
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 0 wait state */
+ FLASH_SetLatency(FLASH_Latency_0);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK */
+ RCC_PCLK1Config(RCC_HCLK_Div1);
+
+ /* Select HSE as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_HSE);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x04)
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock configuration.
+ User can add here some code to deal with this error */
+
+ /* Go to infinite loop */
+ while (1)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : SetSysClockTo20
+* Description : Sets System clock frequency to 20MHz and configure HCLK, PCLK2
+* and PCLK1 prescalers.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SetSysClockTo20(void)
+{
+ /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------------------------*/
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 0 wait state */
+ FLASH_SetLatency(FLASH_Latency_0);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK */
+ RCC_PCLK1Config(RCC_HCLK_Div1);
+
+ /* PLLCLK = (8MHz / 2) * 5 = 20 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div2, RCC_PLLMul_5);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock configuration.
+ User can add here some code to deal with this error */
+
+ /* Go to infinite loop */
+ while (1)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : SetSysClockTo36
+* Description : Sets System clock frequency to 36MHz and configure HCLK, PCLK2
+* and PCLK1 prescalers.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SetSysClockTo36(void)
+{
+ /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------------------------*/
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 1 wait state */
+ FLASH_SetLatency(FLASH_Latency_1);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK */
+ RCC_PCLK1Config(RCC_HCLK_Div1);
+
+ /* PLLCLK = (8MHz / 2) * 9 = 36 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div2, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock configuration.
+ User can add here some code to deal with this error */
+
+ /* Go to infinite loop */
+ while (1)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : SetSysClockTo48
+* Description : Sets System clock frequency to 48MHz and configure HCLK, PCLK2
+* and PCLK1 prescalers.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SetSysClockTo48(void)
+{
+ /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------------------------*/
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 1 wait state */
+ FLASH_SetLatency(FLASH_Latency_1);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 6 = 48 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_6);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock configuration.
+ User can add here some code to deal with this error */
+
+ /* Go to infinite loop */
+ while (1)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : SetSysClockTo72
+* Description : Sets System clock frequency to 72MHz and configure HCLK, PCLK2
+* and PCLK1 prescalers.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SetSysClockTo72(void)
+{
+ /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------------------------*/
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock configuration.
+ User can add here some code to deal with this error */
+
+ /* Go to infinite loop */
+ while (1)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Enable and configure RCC global IRQ channel */
+ NVIC_InitStructure.NVIC_IRQChannel = RCC_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for(; nCount!= 0;nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RCC/main.h b/src/stm32lib/examples/RCC/main.h new file mode 100755 index 0000000..f81b35c --- /dev/null +++ b/src/stm32lib/examples/RCC/main.h @@ -0,0 +1,39 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Header for main.c module
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __MAIN_H
+#define __MAIN_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the desired System clock (SYSCLK)
+ frequency (after reset the HSI is used as SYSCLK source) */
+//#define SYSCLK_HSE
+//#define SYSCLK_FREQ_20MHz
+//#define SYSCLK_FREQ_36MHz
+//#define SYSCLK_FREQ_48MHz
+#define SYSCLK_FREQ_72MHz
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __MAIN_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RCC/platform_config.h b/src/stm32lib/examples/RCC/platform_config.h new file mode 100755 index 0000000..0bc5169 --- /dev/null +++ b/src/stm32lib/examples/RCC/platform_config.h @@ -0,0 +1,44 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RCC/readme.txt b/src/stm32lib/examples/RCC/readme.txt new file mode 100755 index 0000000..e1928a0 --- /dev/null +++ b/src/stm32lib/examples/RCC/readme.txt @@ -0,0 +1,77 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the RCC Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to configure the System clock(SYSCLK) to have different
+frequencies: 20MHz, 36MHz, 48MHz and 72MHz. The SYSCLK frequency is selected by
+user in main.h file
+It shows how to use, for debug purpose, the RCC_GetClocksFreq function to retrieve
+the current status and frequencies of different on chip clocks. You can see the
+RCC_ClockFreq structure content, which hold the frequencies of different on chip
+clocks, using your toolchain debugger.
+
+This example handles also the High Speed External clock (HSE) failure detection:
+when the HSE clock disappears (broken or disconnected external Quartz); HSE, PLL
+are disabled (but no change on PLL config), HSI selected as system clock source
+and an interrupt (NMI) is generated. In the NMI ISR, the HSE, HSE ready interrupt
+are enabled and once HSE clock recover, the HSERDY interrupt is generated and in
+the RCC ISR routine the system clock is reconfigured to its previous state (before
+HSE clock failure). You can monitor the HSE clock on the MCO pin (PA.08).
+
+Four LEDs connected to the GPIO_LED Pin 6, Pin 7, Pin 8 and Pin 9 are toggled
+with a timing defined by the Delay function.
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PC.06, PC.07, PC.08
+ and PC.09 pins
+
+ + STM3210E-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PF.06, PF0.7, PF.08
+ and PF.09 pins
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/RCC/stm32f10x_conf.h b/src/stm32lib/examples/RCC/stm32f10x_conf.h new file mode 100755 index 0000000..e7a99be --- /dev/null +++ b/src/stm32lib/examples/RCC/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RCC/stm32f10x_it.c b/src/stm32lib/examples/RCC/stm32f10x_it.c new file mode 100755 index 0000000..738a06d --- /dev/null +++ b/src/stm32lib/examples/RCC/stm32f10x_it.c @@ -0,0 +1,865 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "main.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+ /* This interrupt is generated when HSE clock fails */
+
+ if (RCC_GetITStatus(RCC_IT_CSS) != RESET)
+ {/* At this stage: HSE, PLL are disabled (but no change on PLL config) and HSI
+ is selected as system clock source */
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Enable HSE Ready interrupt */
+ RCC_ITConfig(RCC_IT_HSERDY, ENABLE);
+
+#ifndef SYSCLK_HSE
+ /* Enable PLL Ready interrupt */
+ RCC_ITConfig(RCC_IT_PLLRDY, ENABLE);
+#endif
+
+ /* Clear Clock Security System interrupt pending bit */
+ RCC_ClearITPendingBit(RCC_IT_CSS);
+
+ /* Once HSE clock recover, the HSERDY interrupt is generated and in the RCC ISR
+ routine the system clock will be reconfigured to its previous state (before
+ HSE clock failure) */
+ }
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+ if(RCC_GetITStatus(RCC_IT_HSERDY) != RESET)
+ {
+ /* Clear HSERDY interrupt pending bit */
+ RCC_ClearITPendingBit(RCC_IT_HSERDY);
+
+ /* Check if the HSE clock is still available */
+ if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET)
+ {
+#ifdef SYSCLK_HSE
+ /* Select HSE as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_HSE);
+#else
+ /* Enable PLL: once the PLL is ready the PLLRDY interrupt is generated */
+ RCC_PLLCmd(ENABLE);
+#endif
+ }
+ }
+
+ if(RCC_GetITStatus(RCC_IT_PLLRDY) != RESET)
+ {
+ /* Clear PLLRDY interrupt pending bit */
+ RCC_ClearITPendingBit(RCC_IT_PLLRDY);
+
+ /* Check if the PLL is still locked */
+ if (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) != RESET)
+ {
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RCC/stm32f10x_it.h b/src/stm32lib/examples/RCC/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/RCC/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RTC/Calendar/main.c b/src/stm32lib/examples/RTC/Calendar/main.c new file mode 100755 index 0000000..48d13dd --- /dev/null +++ b/src/stm32lib/examples/RTC/Calendar/main.c @@ -0,0 +1,513 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+#include <stdio.h>
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define RTCClockOutput_Enable /* RTC Clock/64 is output on tamper pin(PC.13) */
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+vu32 TimeDisplay = 0;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void USART_Configuration(void);
+void RTC_Configuration(void);
+void NVIC_Configuration(void);
+u32 Time_Regulate(void);
+void Time_Adjust(void);
+void Time_Show(void);
+void Time_Display(u32 TimeVar);
+u8 USART_Scanf(u32 value);
+
+#ifdef __GNUC__
+/* With GCC/RAISONANCE, small printf (option LD Linker->Libraries->Small printf
+ set to 'Yes') calls __io_putchar() */
+#define PUTCHAR_PROTOTYPE int __io_putchar(int ch)
+#else
+#define PUTCHAR_PROTOTYPE int fputc(int ch, FILE *f)
+#endif /* __GNUC__ */
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIOs */
+ GPIO_Configuration();
+
+ /* Configure the USART1 */
+ USART_Configuration();
+
+ if (BKP_ReadBackupRegister(BKP_DR1) != 0xA5A5)
+ {
+ /* Backup data register value is not correct or not yet programmed (when
+ the first time the program is executed) */
+
+ printf("\r\n\n RTC not yet configured....");
+
+ /* RTC Configuration */
+ RTC_Configuration();
+
+ printf("\r\n RTC configured....");
+
+ /* Adjust time by values entred by the user on the hyperterminal */
+ Time_Adjust();
+
+ BKP_WriteBackupRegister(BKP_DR1, 0xA5A5);
+ }
+ else
+ {
+ /* Check if the Power On Reset flag is set */
+ if (RCC_GetFlagStatus(RCC_FLAG_PORRST) != RESET)
+ {
+ printf("\r\n\n Power On Reset occurred....");
+ }
+ /* Check if the Pin Reset flag is set */
+ else if (RCC_GetFlagStatus(RCC_FLAG_PINRST) != RESET)
+ {
+ printf("\r\n\n External Reset occurred....");
+ }
+
+ printf("\r\n No need to configure RTC....");
+ /* Wait for RTC registers synchronization */
+ RTC_WaitForSynchro();
+
+ /* Enable the RTC Second */
+ RTC_ITConfig(RTC_IT_SEC, ENABLE);
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+ }
+
+#ifdef RTCClockOutput_Enable
+ /* Enable PWR and BKP clocks */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE);
+
+ /* Allow access to BKP Domain */
+ PWR_BackupAccessCmd(ENABLE);
+
+ /* Disable the Tamper Pin */
+ BKP_TamperPinCmd(DISABLE); /* To output RTCCLK/64 on Tamper pin, the tamper
+ functionality must be disabled */
+
+ /* Enable RTC Clock Output on Tamper Pin */
+ BKP_RTCOutputConfig(BKP_RTCOutputSource_CalibClock);
+#endif
+
+ /* Clear reset flags */
+ RCC_ClearFlag();
+
+ /* Display time in infinite loop */
+ Time_Show();
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* Enable USART1, GPIOA, GPIOC and GPIO_LED clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA |
+ RCC_APB2Periph_GPIO_LED | RCC_APB2Periph_GPIOC , ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Configure one bit for preemption priority */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
+
+ /* Enable the RTC Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = RTC_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure GPIO_LED pin 6 as Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ /* Configure USART1 Tx (PA.09) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART1 Rx (PA.10) as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : RTC_Configuration
+* Description : Configures the RTC.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_Configuration(void)
+{
+ /* Enable PWR and BKP clocks */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE);
+
+ /* Allow access to BKP Domain */
+ PWR_BackupAccessCmd(ENABLE);
+
+ /* Reset Backup Domain */
+ BKP_DeInit();
+
+ /* Enable LSE */
+ RCC_LSEConfig(RCC_LSE_ON);
+ /* Wait till LSE is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_LSERDY) == RESET)
+ {}
+
+ /* Select LSE as RTC Clock Source */
+ RCC_RTCCLKConfig(RCC_RTCCLKSource_LSE);
+
+ /* Enable RTC Clock */
+ RCC_RTCCLKCmd(ENABLE);
+
+ /* Wait for RTC registers synchronization */
+ RTC_WaitForSynchro();
+
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+
+ /* Enable the RTC Second */
+ RTC_ITConfig(RTC_IT_SEC, ENABLE);
+
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+
+ /* Set RTC prescaler: set RTC period to 1sec */
+ RTC_SetPrescaler(32767); /* RTC period = RTCCLK/RTC_PR = (32.768 KHz)/(32767+1) */
+
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+}
+
+/*******************************************************************************
+* Function Name : Time_Regulate
+* Description : Returns the time entered by user, using Hyperterminal.
+* Input : None
+* Output : None
+* Return : Current time RTC counter value
+*******************************************************************************/
+u32 Time_Regulate(void)
+{
+ u32 Tmp_HH = 0xFF, Tmp_MM = 0xFF, Tmp_SS = 0xFF;
+
+ printf("\r\n==============Time Settings=====================================");
+ printf("\r\n Please Set Hours");
+
+ while (Tmp_HH == 0xFF)
+ {
+ Tmp_HH = USART_Scanf(23);
+ }
+ printf(": %d", Tmp_HH);
+ printf("\r\n Please Set Minutes");
+ while (Tmp_MM == 0xFF)
+ {
+ Tmp_MM = USART_Scanf(59);
+ }
+ printf(": %d", Tmp_MM);
+ printf("\r\n Please Set Seconds");
+ while (Tmp_SS == 0xFF)
+ {
+ Tmp_SS = USART_Scanf(59);
+ }
+ printf(": %d", Tmp_SS);
+
+ /* Return the value to store in RTC counter register */
+ return((Tmp_HH*3600 + Tmp_MM*60 + Tmp_SS));
+}
+
+/*******************************************************************************
+* Function Name : Time_Adjust
+* Description : Adjusts time.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void Time_Adjust(void)
+{
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+ /* Change the current time */
+ RTC_SetCounter(Time_Regulate());
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+}
+
+/*******************************************************************************
+* Function Name : Time_Display
+* Description : Displays the current time.
+* Input : - TimeVar: RTC counter value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Time_Display(u32 TimeVar)
+{
+ u32 THH = 0, TMM = 0, TSS = 0;
+
+ /* Compute hours */
+ THH = TimeVar / 3600;
+ /* Compute minutes */
+ TMM = (TimeVar % 3600) / 60;
+ /* Compute seconds */
+ TSS = (TimeVar % 3600) % 60;
+
+ printf("Time: %0.2d:%0.2d:%0.2d\r", THH, TMM, TSS);
+}
+
+/*******************************************************************************
+* Function Name : Time_Show
+* Description : Shows the current time (HH:MM:SS) on the Hyperterminal.
+* Input : None
+* Output : None
+* Return : None
+******************************************************************************/
+void Time_Show(void)
+{
+ printf("\n\r");
+
+ /* Infinite loop */
+ while (1)
+ {
+ /* If 1s has paased */
+ if (TimeDisplay == 1)
+ {
+ /* Display current time */
+ Time_Display(RTC_GetCounter());
+ TimeDisplay = 0;
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_Configuration
+* Description : Configures the USART1.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_Configuration(void)
+{
+ USART_InitTypeDef USART_InitStructure;
+
+ /* Enable USARTx clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
+
+ /* USART1 configuration ----------------------------------------------------*/
+ /* USART1 configured as follow:
+ - BaudRate = 115200 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Receive and transmit enabled
+ - Hardware flow control disabled (RTS and CTS signals)
+ */
+ USART_InitStructure.USART_BaudRate = 115200;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_No;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+
+ USART_Init(USART1, &USART_InitStructure);
+
+ /* Enable USART1 */
+ USART_Cmd(USART1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : PUTCHAR_PROTOTYPE
+* Description : Retargets the C library printf function to the USART.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+PUTCHAR_PROTOTYPE
+{
+ /* Place your implementation of fputc here */
+ /* e.g. write a character to the USART */
+ USART_SendData(USART1, (u8) ch);
+
+ /* Loop until the end of transmission */
+ while (USART_GetFlagStatus(USART1, USART_FLAG_TC) == RESET)
+ {}
+
+ return ch;
+}
+
+/*******************************************************************************
+* Function Name : USART_Scanf
+* Description : Gets numeric values from the hyperterminal.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+u8 USART_Scanf(u32 value)
+{
+ u32 index = 0;
+ u32 tmp[2] = {0, 0};
+
+ while (index < 2)
+ {
+ /* Loop until RXNE = 1 */
+ while (USART_GetFlagStatus(USART1, USART_FLAG_RXNE) == RESET)
+ {}
+ tmp[index++] = (USART_ReceiveData(USART1));
+ if ((tmp[index - 1] < 0x30) || (tmp[index - 1] > 0x39))
+ {
+ printf("\n\rPlease enter valid number between 0 and 9");
+ index--;
+ }
+ }
+ /* Calculate the Corresponding value */
+ index = (tmp[1] - 0x30) + ((tmp[0] - 0x30) * 10);
+ /* Checks */
+ if (index > value)
+ {
+ printf("\n\rPlease enter valid number between 0 and %d", value);
+ return 0xFF;
+ }
+ return index;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RTC/Calendar/platform_config.h b/src/stm32lib/examples/RTC/Calendar/platform_config.h new file mode 100755 index 0000000..3b73964 --- /dev/null +++ b/src/stm32lib/examples/RTC/Calendar/platform_config.h @@ -0,0 +1,44 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+//#define USE_STM3210B_EVAL
+#define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RTC/Calendar/readme.txt b/src/stm32lib/examples/RTC/Calendar/readme.txt new file mode 100755 index 0000000..1b2d83c --- /dev/null +++ b/src/stm32lib/examples/RTC/Calendar/readme.txt @@ -0,0 +1,115 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the RTC Calendar Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example demonstrates and explains how to use the RTC peripheral.
+As an application example, it demonstrates how to setup the RTC peripheral, in terms
+of prescaler and interrupts, to be used to keep time and to generate Second interrupt.
+
+The Low Speed External (LSE) clock is used as RTC clock source.
+The RTC clock can be output on the Tamper pin (PC.13). To enable this functionality,
+uncomment the corresponding line: #define RTCClockOutput_Enable in the main.c file.
+
+The RTC is in the backup (BKP) domain, still powered by VBAT when VDD is switched off,
+so the RTC configuration is not lost if a battery is connected to the VBAT pin.
+A key value is written in backup data register1 (BKP_DR1) to indicate if the RTC
+is already configured.
+
+The program behaves as follows:
+1. After startup the program checks the backup data register1 value:
+ – register1 value not correct: (BKP_DR1 value is not correct or has not yet
+ been programmed when the program is executed for the first time) the RTC is
+ configured and the user is asked to set the time (entered on HyperTerminal).
+ – register1 value correct: this means that the RTC is configured and the time
+ is displayed on HyperTerminal.
+2. When an External Reset occurs the BKP domain is not reset and the RTC configuration
+ is not lost.
+3. When power on reset occurs:
+ – If a battery is connected to the VBAT pin: the BKP domain is not reset and
+ the RTC configuration is not lost.
+ – If no battery is connected to the VBAT pin: the BKP domain is reset and the
+ RTC configuration is lost.
+
+In the RTC interrupt service routine, a specific GPIO pin toggles every 1 s.
+The C library printf function is retargeted to the USART1, that is, the printf
+message is output to the HyperTerminal using USART1.
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1 led connected to PC.06.
+ - The USART1 signals (Rx, Tx) must be connected to a DB9 connector using a RS232
+ transceiver.
+ - Connect a null-modem female/female RS232 cable between the DB9 connector
+ (CN6 on STM3210B-EVAL board) and PC serial port.
+ - Hyperterminal configuration:
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - BaudRate = 115200 baud
+ - flow control: None
+ - Connect a 3V battery on Vbat pin (already mounted on STM3210B-EVAL board)
+
+ + STM3210E-EVAL
+ - Use LD1 led connected to PF.06.
+ - The USART1 signals (Rx, Tx) must be connected to a DB9 connector using a RS232
+ transceiver.
+ - Connect a null-modem female/female RS232 cable between the DB9 connector
+ (CN12 on STM3210B-EVAL board) and PC serial port.
+ - Hyperterminal configuration:
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - BaudRate = 115200 baud
+ - flow control: None
+ - Connect a 3V battery on Vbat pin (already mounted on STM3210E-EVAL board)
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_rtc.c
+ + stm32f10x_bkp.c
+ + stm32f10x_pwr.c
+ + stm32f10x_nvic.c
+ + stm32f10x_usart.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/RTC/Calendar/stm32f10x_conf.h b/src/stm32lib/examples/RTC/Calendar/stm32f10x_conf.h new file mode 100755 index 0000000..c98b4de --- /dev/null +++ b/src/stm32lib/examples/RTC/Calendar/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+#define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RTC/Calendar/stm32f10x_it.c b/src/stm32lib/examples/RTC/Calendar/stm32f10x_it.c new file mode 100755 index 0000000..f1ea185 --- /dev/null +++ b/src/stm32lib/examples/RTC/Calendar/stm32f10x_it.c @@ -0,0 +1,766 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+extern vu32 TimeDisplay;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+ if (RTC_GetITStatus(RTC_IT_SEC) != RESET)
+ {
+ /* Clear the RTC Second interrupt */
+ RTC_ClearITPendingBit(RTC_IT_SEC);
+
+ /* Toggle GPIO_LED pin 6 each 1s */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_6, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_6)));
+
+ /* Enable time update */
+ TimeDisplay = 1;
+
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+ /* Reset RTC Counter when Time is 23:59:59 */
+ if (RTC_GetCounter() == 0x00015180)
+ {
+ RTC_SetCounter(0x0);
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RTC/Calendar/stm32f10x_it.h b/src/stm32lib/examples/RTC/Calendar/stm32f10x_it.h new file mode 100755 index 0000000..58da1cc --- /dev/null +++ b/src/stm32lib/examples/RTC/Calendar/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RTC/LSI_Calib/main.c b/src/stm32lib/examples/RTC/LSI_Calib/main.c new file mode 100755 index 0000000..612bb5f --- /dev/null +++ b/src/stm32lib/examples/RTC/LSI_Calib/main.c @@ -0,0 +1,323 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include <stdio.h>
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define RTCClockOutput_Enable /* RTC Clock/64 is output on tamper pin(PC.13) */
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_ICInitTypeDef TIM_ICInitStructure;
+RCC_ClocksTypeDef RCC_Clocks;
+vu32 PeriodValue = 0, LsiFreq = 0;
+vu32 OperationComplete = 0;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void RTC_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIOs */
+ GPIO_Configuration();
+
+ /* RTC Configuration */
+ RTC_Configuration();
+
+ /* Wait until Key Push button is pressed */
+ while (GPIO_ReadInputDataBit(GPIOG, GPIO_Pin_8) != 0)
+ {}
+
+ /* Get the Frequency value */
+ RCC_GetClocksFreq(&RCC_Clocks);
+
+ /* Enable TIM5 APB1 clocks */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE);
+
+ /* Connect internally the TM5_CH4 Input Capture to the LSI clock output */
+ GPIO_PinRemapConfig(GPIO_Remap_TIM5CH4_LSI, ENABLE);
+
+ /* TIM5 Time base configuration */
+ TIM_TimeBaseStructure.TIM_Prescaler = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseStructure.TIM_Period = 0xFFFF;
+ TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
+ TIM_TimeBaseInit(TIM5, &TIM_TimeBaseStructure);
+
+ /* TIM5 Channel4 Input capture Mode configuration */
+ TIM_ICInitStructure.TIM_Channel = TIM_Channel_4;
+ TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
+ TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
+ TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
+ TIM_ICInitStructure.TIM_ICFilter = 0;
+ TIM_ICInit(TIM5, &TIM_ICInitStructure);
+
+ /* Reinitialize the index for the interrupt */
+ OperationComplete = 0;
+
+ /* Enable the TIM5 Input Capture counter */
+ TIM_Cmd(TIM5, ENABLE);
+ /* Reset all TIM5 flags */
+ TIM5->SR = 0;
+ /* Enable the TIM5 channel 4 */
+ TIM_ITConfig(TIM5, TIM_IT_CC4, ENABLE);
+
+ /* Wait the TIM5 measuring operation to be completed */
+ while (OperationComplete != 2)
+ {}
+
+ /* Compute the actual frequency of the LSI. (TIM5_CLK = 2 * PCLK1) */
+ if (PeriodValue != 0)
+ {
+ LsiFreq = (u32)((u32)(RCC_Clocks.PCLK1_Frequency * 2) / (u32)PeriodValue);
+ }
+
+ /* Adjust the RTC prescaler value */
+ RTC_SetPrescaler(LsiFreq - 1);
+
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+
+ /* Set GPIOF pin 7 */
+ GPIO_SetBits(GPIOF, GPIO_Pin_7);
+
+ while (1)
+ {
+ /* Inifinite loop */
+ }
+
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* Enable GPIOG, GPIOF and AFIO clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOG | RCC_APB2Periph_GPIOF
+ | RCC_APB2Periph_AFIO, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Configure one bit for preemption priority */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
+
+ /* Enable the RTC Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = RTC_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Enable the TIM5 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = TIM5_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure GPIOF pin 6 and pin 7 as Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOF, &GPIO_InitStructure);
+
+ /* Configure Key Button GPIO Pin as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOG, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : RTC_Configuration
+* Description : Configures the RTC.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_Configuration(void)
+{
+ /* Enable PWR and BKP clocks */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE);
+
+ /* Allow access to BKP Domain */
+ PWR_BackupAccessCmd(ENABLE);
+
+ /* Reset Backup Domain */
+ BKP_DeInit();
+
+ /* Enable the LSI OSC */
+ RCC_LSICmd(ENABLE);
+ /* Wait till LSI is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_LSIRDY) == RESET)
+ {}
+ /* Select the RTC Clock Source */
+ RCC_RTCCLKConfig(RCC_RTCCLKSource_LSI);
+
+ /* Enable RTC Clock */
+ RCC_RTCCLKCmd(ENABLE);
+
+ /* Wait for RTC registers synchronization */
+ RTC_WaitForSynchro();
+
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+
+ /* Enable the RTC Second */
+ RTC_ITConfig(RTC_IT_SEC, ENABLE);
+
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+
+ /* Set RTC prescaler: set RTC period to 1sec */
+ RTC_SetPrescaler(40000);
+
+ /* Wait until last write operation on RTC registers has finished */
+ RTC_WaitForLastTask();
+
+ /* To output second signal on Tamper pin, the tamper functionality
+ must be disabled (by default this functionality is disabled) */
+ BKP_TamperPinCmd(DISABLE);
+
+ /* Enable the RTC Second Output on Tamper Pin */
+ BKP_RTCOutputConfig(BKP_RTCOutputSource_Second);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RTC/LSI_Calib/readme.txt b/src/stm32lib/examples/RTC/LSI_Calib/readme.txt new file mode 100755 index 0000000..7385bda --- /dev/null +++ b/src/stm32lib/examples/RTC/LSI_Calib/readme.txt @@ -0,0 +1,82 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the RTC LSI_Calib Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example demonstrates and explains how to use the LSI clock source auto
+calibration to get a precise RTC clock.
+As an application example, it demonstrates how to configure the TIM5 timer
+internally connected to LSI clock output, in order to adjust the RTC prescaler.
+
+The Low Speed External (LSI) clock is used as RTC clock source.
+After reset, the RTC prescaler is set with the default value (40000).
+The inaccuracy of the LSI clock causes the Second signal to be inaccurate. This
+signal is output on the Tamper pin (PC.13) and can be measured by on oscilloscope
+or a frequencymeter.
+
+The program waits until the PG.08 pin level goes low (push Key button on STM3210E-EVAL
+board) to begin the auto calibration procedure:
+ - Configure the TIM5 to remap internally the TIM5 Channel 4 Input Capture to the
+ LSI clock output.
+ - Enable the TIM5 Input Capture interrupt: after one cycle of LSI clock, the
+ period value is stored in a variable and compared to the HCLK clock to get
+ its real value.
+ - The RTC prescaler is adjusted with this LSI frequency value so that the RTC
+ Second value become more accurate.
+ - When calibration is done a led connected to PF.07 is turned ON to indicate the
+ end of this operation. At this moment, you can monitor the Second signal on
+ an oscilloscope to measure its accuracy again.
+
+The Seconds signal can be monitored either on Tamper pin or on a specific PF.06
+pin toggled into the RTC Seconds interrupt service routine.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board and can be
+easily tailored to any other hardware.
+
+Use LD1 and LD2 leds connected respectively to PF.06 and PF.07 pins, and the Key
+push button connected to PG.08 pin.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_rtc.c
+ + stm32f10x_tim.c
+ + stm32f10x_bkp.c
+ + stm32f10x_pwr.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/RTC/LSI_Calib/stm32f10x_conf.h b/src/stm32lib/examples/RTC/LSI_Calib/stm32f10x_conf.h new file mode 100755 index 0000000..d041b20 --- /dev/null +++ b/src/stm32lib/examples/RTC/LSI_Calib/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+#define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RTC/LSI_Calib/stm32f10x_it.c b/src/stm32lib/examples/RTC/LSI_Calib/stm32f10x_it.c new file mode 100755 index 0000000..7613daf --- /dev/null +++ b/src/stm32lib/examples/RTC/LSI_Calib/stm32f10x_it.c @@ -0,0 +1,771 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V3.0
+* Date : 02/25/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+vu16 tmpCC4[2] = {0, 0};
+extern vu32 OperationComplete;
+extern vu32 PeriodValue;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+ if (RTC_GetITStatus(RTC_IT_SEC) != RESET)
+ {
+ /* Toggle GPIOF pin 6 connected to LD1 */
+ GPIO_WriteBit(GPIOF, GPIO_Pin_6, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIOF, GPIO_Pin_6)));
+
+ /* Clear Interrupt pending bit */
+ RTC_ClearITPendingBit(RTC_FLAG_SEC);
+ }
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+ if (TIM_GetITStatus(TIM5, TIM_IT_CC4) == SET)
+ {
+ tmpCC4[OperationComplete++] = (u16)(TIM5->CCR4);
+
+ TIM_ClearITPendingBit(TIM5, TIM_IT_CC4);
+
+ if (OperationComplete >= 2)
+ {
+ /* Compute the period length */
+ PeriodValue = (u16)(tmpCC4[1] - tmpCC4[0] + 1);
+
+ /* Disable the interrupt */
+ TIM_ITConfig(TIM5, TIM_IT_CC4, DISABLE);
+ TIM_Cmd(TIM5, DISABLE);
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/RTC/LSI_Calib/stm32f10x_it.h b/src/stm32lib/examples/RTC/LSI_Calib/stm32f10x_it.h new file mode 100755 index 0000000..58da1cc --- /dev/null +++ b/src/stm32lib/examples/RTC/LSI_Calib/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SDIO/main.c b/src/stm32lib/examples/SDIO/main.c new file mode 100755 index 0000000..73259d0 --- /dev/null +++ b/src/stm32lib/examples/SDIO/main.c @@ -0,0 +1,329 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "sdcard.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define BlockSize 512 /* Block Size in Bytes */
+#define BufferWordsSize (BlockSize >> 2)
+
+#define NumberOfBlocks 2 /* For Multi Blocks operation (Read/Write) */
+#define MultiBufferWordsSize ((BlockSize * NumberOfBlocks) >> 2)
+
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+SD_CardInfo SDCardInfo;
+u32 Buffer_Block_Tx[BufferWordsSize], Buffer_Block_Rx[BufferWordsSize];
+u32 Buffer_MultiBlock_Tx[MultiBufferWordsSize], Buffer_MultiBlock_Rx[MultiBufferWordsSize];
+volatile TestStatus EraseStatus = FAILED, TransferStatus1 = FAILED, TransferStatus2 = FAILED;
+SD_Error Status = SD_OK;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+void Fill_Buffer(u32 *pBuffer, u16 BufferLenght, u32 Offset);
+TestStatus Buffercmp(u32* pBuffer1, u32* pBuffer2, u16 BufferLength);
+TestStatus eBuffercmp(u32* pBuffer, u16 BufferLength);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* Clock Config */
+ RCC_Configuration();
+
+ /* Interrupt Config */
+ NVIC_Configuration();
+
+ /*-------------------------- SD Init ----------------------------- */
+ Status = SD_Init();
+
+ if (Status == SD_OK)
+ {
+ /*----------------- Read CSD/CID MSD registers ------------------*/
+ Status = SD_GetCardInfo(&SDCardInfo);
+ }
+
+ if (Status == SD_OK)
+ {
+ /*----------------- Select Card --------------------------------*/
+ Status = SD_SelectDeselect((u32) (SDCardInfo.RCA << 16));
+ }
+
+ if (Status == SD_OK)
+ {
+ Status = SD_EnableWideBusOperation(SDIO_BusWide_4b);
+ }
+
+ /*------------------- Block Erase -------------------------------*/
+ if (Status == SD_OK)
+ {
+ /* Erase NumberOfBlocks Blocks of WRITE_BL_LEN(512 Bytes) */
+ Status = SD_Erase(0x00, (BlockSize * NumberOfBlocks));
+ }
+
+ /* Set Device Transfer Mode to DMA */
+ if (Status == SD_OK)
+ {
+ Status = SD_SetDeviceMode(SD_DMA_MODE);
+ }
+
+ if (Status == SD_OK)
+ {
+ Status = SD_ReadMultiBlocks(0x00, Buffer_MultiBlock_Rx, BlockSize, NumberOfBlocks);
+ }
+
+ if (Status == SD_OK)
+ {
+ EraseStatus = eBuffercmp(Buffer_MultiBlock_Rx, MultiBufferWordsSize);
+ }
+
+ /*------------------- Block Read/Write --------------------------*/
+ /* Fill the buffer to send */
+ Fill_Buffer(Buffer_Block_Tx, BufferWordsSize, 0xFFFF);
+
+
+ if (Status == SD_OK)
+ {
+ /* Write block of 512 bytes on address 0 */
+ Status = SD_WriteBlock(0x00, Buffer_Block_Tx, BlockSize);
+ }
+
+ if (Status == SD_OK)
+ {
+ /* Read block of 512 bytes from address 0 */
+ Status = SD_ReadBlock(0x00, Buffer_Block_Rx, BlockSize);
+ }
+
+ if (Status == SD_OK)
+ {
+ /* Check the corectness of written dada */
+ TransferStatus1 = Buffercmp(Buffer_Block_Tx, Buffer_Block_Rx, BufferWordsSize);
+ }
+
+ /*--------------- Multiple Block Read/Write ---------------------*/
+ /* Fill the buffer to send */
+ Fill_Buffer(Buffer_MultiBlock_Tx, MultiBufferWordsSize, 0x0);
+
+ if (Status == SD_OK)
+ {
+ /* Write multiple block of many bytes on address 0 */
+ Status = SD_WriteMultiBlocks(0x00, Buffer_MultiBlock_Tx, BlockSize, NumberOfBlocks);
+ }
+
+ if (Status == SD_OK)
+ {
+ /* Read block of many bytes from address 0 */
+ Status = SD_ReadMultiBlocks(0x00, Buffer_MultiBlock_Rx, BlockSize, NumberOfBlocks);
+ }
+
+ if (Status == SD_OK)
+ {
+ /* Check the corectness of written dada */
+ TransferStatus2 = Buffercmp(Buffer_MultiBlock_Tx, Buffer_MultiBlock_Rx, MultiBufferWordsSize);
+ }
+
+ /* Infinite loop */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Config
+* Description : Configures SDIO IRQ channel.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+ /* Configure the NVIC Preemption Priority Bits */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
+
+ NVIC_InitStructure.NVIC_IRQChannel = SDIO_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u32* pBuffer1, u32* pBuffer2, u16 BufferLength)
+{
+ while (BufferLength--)
+ {
+ if (*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+/*******************************************************************************
+* Function name : Fill_Buffer
+* Description : Fills buffer with user predefined data.
+* Input : - pBuffer: pointer on the Buffer to fill
+* - BufferLenght: size of the buffer to fill
+* - Offset: first value to fill on the Buffer
+* Output : None
+* Return : None
+*******************************************************************************/
+void Fill_Buffer(u32 *pBuffer, u16 BufferLenght, u32 Offset)
+{
+ u16 index = 0;
+
+ /* Put in global buffer same values */
+ for (index = 0; index < BufferLenght; index++ )
+ {
+ pBuffer[index] = index + Offset;
+ }
+}
+
+/*******************************************************************************
+* Function name : eBuffercmp
+* Description : Checks if a buffer has all its values are equal to zero.
+* Input : - pBuffer: buffer to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer values are zero
+* FAILED: At least one value from pBuffer buffer is diffrent
+* from zero.
+*******************************************************************************/
+TestStatus eBuffercmp(u32* pBuffer, u16 BufferLength)
+{
+ while (BufferLength--)
+ {
+ if (*pBuffer != 0x00)
+ {
+ return FAILED;
+ }
+
+ pBuffer++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SDIO/readme.txt b/src/stm32lib/examples/SDIO/readme.txt new file mode 100755 index 0000000..54d6cd1 --- /dev/null +++ b/src/stm32lib/examples/SDIO/readme.txt @@ -0,0 +1,79 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the SDIO Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a basic example of how to use the SDIO firmware library and
+an associate driver to perform read/write operations on the SD Card memory
+mounted on the STM3210E-EVAL board.
+Below is a description of the different example steps:
+ - Configure the SDIO according to the desired SDIO_CK clock frequency.
+ - Reset the SD Card
+ - Identify the SD Card
+ - Initializes the SD Card
+ - Get the SD Card Info
+ - Select the SD Card
+ - Enable the Wide Bus mode (4-bit data)
+ - Erase the correponding blocks
+ - Read the Erased blocks
+ - Test if the corresponding Blocks are well erased: check if the EraseStatus
+ variable is equal to PASSED.
+ - Set the Data Transfer Mode to DMA
+ - Write a single Block
+ - Read a single Block
+ - Comapare the written Block and the read one: check if the TransferStatus1
+ variable is equal to PASSED.
+ - Write multiple Blocks (2)
+ - Read multiple Blocks (2)
+ - Comapare the written Blocks and the read one: check if the TransferStatus2
+ variable is equal to PASSED.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+sdcard.c SD Card Driver file
+sdcard.h Header for sdcard.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210E-EVAL evaluation board and can be
+easily tailored to any other hardware.
+
+Note: make sure that the Jumper 17 (JP17) is closed and Jumper 20 (JP20) is open
+ in STM3210E-EVAL
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_sdio.c
+ + stm32f10x_dma.c
+
+- Link all compiled files and load your image into either RAM or Flash
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/SDIO/sdcard.c b/src/stm32lib/examples/SDIO/sdcard.c new file mode 100755 index 0000000..c837e79 --- /dev/null +++ b/src/stm32lib/examples/SDIO/sdcard.c @@ -0,0 +1,2895 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : sdcard.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides all the SD Card driver firmware
+* functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "sdcard.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define NULL 0
+#define SDIO_STATIC_FLAGS ((u32)0x000005FF)
+#define SDIO_CMD0TIMEOUT ((u32)0x00002710)
+#define SDIO_FIFO_Address ((u32)0x40018080)
+
+/* Mask for errors Card Status R1 (OCR Register) */
+#define SD_OCR_ADDR_OUT_OF_RANGE ((u32)0x80000000)
+#define SD_OCR_ADDR_MISALIGNED ((u32)0x40000000)
+#define SD_OCR_BLOCK_LEN_ERR ((u32)0x20000000)
+#define SD_OCR_ERASE_SEQ_ERR ((u32)0x10000000)
+#define SD_OCR_BAD_ERASE_PARAM ((u32)0x08000000)
+#define SD_OCR_WRITE_PROT_VIOLATION ((u32)0x04000000)
+#define SD_OCR_LOCK_UNLOCK_FAILED ((u32)0x01000000)
+#define SD_OCR_COM_CRC_FAILED ((u32)0x00800000)
+#define SD_OCR_ILLEGAL_CMD ((u32)0x00400000)
+#define SD_OCR_CARD_ECC_FAILED ((u32)0x00200000)
+#define SD_OCR_CC_ERROR ((u32)0x00100000)
+#define SD_OCR_GENERAL_UNKNOWN_ERROR ((u32)0x00080000)
+#define SD_OCR_STREAM_READ_UNDERRUN ((u32)0x00040000)
+#define SD_OCR_STREAM_WRITE_OVERRUN ((u32)0x00020000)
+#define SD_OCR_CID_CSD_OVERWRIETE ((u32)0x00010000)
+#define SD_OCR_WP_ERASE_SKIP ((u32)0x00008000)
+#define SD_OCR_CARD_ECC_DISABLED ((u32)0x00004000)
+#define SD_OCR_ERASE_RESET ((u32)0x00002000)
+#define SD_OCR_AKE_SEQ_ERROR ((u32)0x00000008)
+#define SD_OCR_ERRORBITS ((u32)0xFDFFE008)
+
+/* Masks for R6 Response */
+#define SD_R6_GENERAL_UNKNOWN_ERROR ((u32)0x00002000)
+#define SD_R6_ILLEGAL_CMD ((u32)0x00004000)
+#define SD_R6_COM_CRC_FAILED ((u32)0x00008000)
+
+#define SD_VOLTAGE_WINDOW_SD ((u32)0x80100000)
+#define SD_HIGH_CAPACITY ((u32)0x40000000)
+#define SD_STD_CAPACITY ((u32)0x00000000)
+#define SD_CHECK_PATTERN ((u32)0x000001AA)
+
+#define SD_MAX_VOLT_TRIAL ((u32)0x0000FFFF)
+#define SD_ALLZERO ((u32)0x00000000)
+
+#define SD_WIDE_BUS_SUPPORT ((u32)0x00040000)
+#define SD_SINGLE_BUS_SUPPORT ((u32)0x00010000)
+#define SD_CARD_LOCKED ((u32)0x02000000)
+#define SD_CARD_PROGRAMMING ((u32)0x00000007)
+#define SD_CARD_RECEIVING ((u32)0x00000006)
+#define SD_DATATIMEOUT ((u32)0x000FFFFF)
+#define SD_0TO7BITS ((u32)0x000000FF)
+#define SD_8TO15BITS ((u32)0x0000FF00)
+#define SD_16TO23BITS ((u32)0x00FF0000)
+#define SD_24TO31BITS ((u32)0xFF000000)
+#define SD_MAX_DATA_LENGTH ((u32)0x01FFFFFF)
+
+#define SD_HALFFIFO ((u32)0x00000008)
+#define SD_HALFFIFOBYTES ((u32)0x00000020)
+
+/* Command Class Supported */
+#define SD_CCCC_LOCK_UNLOCK ((u32)0x00000080)
+#define SD_CCCC_WRITE_PROT ((u32)0x00000040)
+#define SD_CCCC_ERASE ((u32)0x00000020)
+
+/* Following commands are SD Card Specific commands.
+ SDIO_APP_CMD should be sent before sending these commands. */
+#define SDIO_SEND_IF_COND ((u32)0x00000008)
+
+#define SDIO_MULTIMEDIA_CARD ((u32)0x0)
+#define SDIO_SECURE_DIGITAL_CARD ((u32)0x1)
+#define SDIO_SECURE_DIGITAL_IO_CARD ((u32)0x2)
+#define SDIO_HIGH_SPEED_MULTIMEDIA_CARD ((u32)0x3)
+#define SDIO_SECURE_DIGITAL_IO_COMBO_CARD ((u32)0x4)
+#define SDIO_HIGH_CAPACITY_SD_CARD ((u32)0x5)
+#define SDIO_HIGH_CAPACITY_MMC_CARD ((u32)0x6)
+
+#define SDIO_INIT_CLK_DIV ((u8)0xB2)
+#define SDIO_TRANSFER_CLK_DIV ((u8)0x1)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+static u32 CardType = SDIO_SECURE_DIGITAL_CARD;
+static u32 CSD_Tab[4], CID_Tab[4], RCA = 0;
+static u32 DeviceMode = SD_POLLING_MODE;
+static u32 TotalNumberOfBytes = 0, StopCondition = 0;
+u32 *SrcBuffer, *DestBuffer;
+volatile SD_Error TransferError = SD_OK;
+vu32 TransferEnd = 0;
+vu32 NumberOfBytes = 0;
+SDIO_InitTypeDef SDIO_InitStructure;
+SDIO_CmdInitTypeDef SDIO_CmdInitStructure;
+SDIO_DataInitTypeDef SDIO_DataInitStructure;
+
+/* Private function prototypes -----------------------------------------------*/
+static SD_Error CmdError(void);
+static SD_Error CmdResp1Error(u8 cmd);
+static SD_Error CmdResp7Error(void);
+static SD_Error CmdResp3Error(void);
+static SD_Error CmdResp2Error(void);
+static SD_Error CmdResp6Error(u8 cmd, u16 *prca);
+static SD_Error SDEnWideBus(FunctionalState NewState);
+static SD_Error IsCardProgramming(u8 *pstatus);
+static SD_Error FindSCR(u16 rca, u32 *pscr);
+static u8 convert_from_bytes_to_power_of_two(u16 NumberOfBytes);
+static void GPIO_Configuration(void);
+static void DMA_TxConfiguration(u32 *BufferSRC, u32 BufferSize);
+static void DMA_RxConfiguration(u32 *BufferDST, u32 BufferSize);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : SD_Init
+* Description : Initializes the SD Card and put it into StandBy State (Ready
+* for data transfer).
+* Input : None
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_Init(void)
+{
+ SD_Error errorstatus = SD_OK;
+
+ /* Configure SDIO interface GPIO */
+ GPIO_Configuration();
+
+ /* Enable the SDIO AHB Clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_SDIO, ENABLE);
+
+ /* Enable the DMA2 Clock */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA2, ENABLE);
+
+ SDIO_DeInit();
+
+ errorstatus = SD_PowerON();
+
+ if (errorstatus != SD_OK)
+ {
+ /* CMD Response TimeOut (wait for CMDSENT flag) */
+ return(errorstatus);
+ }
+
+ errorstatus = SD_InitializeCards();
+
+ if (errorstatus != SD_OK)
+ {
+ /* CMD Response TimeOut (wait for CMDSENT flag) */
+ return(errorstatus);
+ }
+
+ /* Configure the SDIO peripheral */
+ /* HCLK = 72 MHz, SDIOCLK = 72 MHz, SDIO_CK = HCLK/(2 + 1) = 24 MHz */
+ SDIO_InitStructure.SDIO_ClockDiv = SDIO_TRANSFER_CLK_DIV;
+ SDIO_InitStructure.SDIO_ClockEdge = SDIO_ClockEdge_Rising;
+ SDIO_InitStructure.SDIO_ClockBypass = SDIO_ClockBypass_Disable;
+ SDIO_InitStructure.SDIO_ClockPowerSave = SDIO_ClockPowerSave_Disable;
+ SDIO_InitStructure.SDIO_BusWide = SDIO_BusWide_1b;
+ SDIO_InitStructure.SDIO_HardwareFlowControl = SDIO_HardwareFlowControl_Disable;
+ SDIO_Init(&SDIO_InitStructure);
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_PowerON
+* Description : Enquires cards about their operating voltage and configures
+* clock controls.
+* Input : None
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_PowerON(void)
+{
+ SD_Error errorstatus = SD_OK;
+ u32 response = 0, count = 0;
+ bool validvoltage = FALSE;
+ u32 SDType = SD_STD_CAPACITY;
+
+ /* Power ON Sequence -------------------------------------------------------*/
+ /* Configure the SDIO peripheral */
+ SDIO_InitStructure.SDIO_ClockDiv = SDIO_INIT_CLK_DIV; /* HCLK = 72MHz, SDIOCLK = 72MHz, SDIO_CK = HCLK/(178 + 2) = 400 KHz */
+ SDIO_InitStructure.SDIO_ClockEdge = SDIO_ClockEdge_Rising;
+ SDIO_InitStructure.SDIO_ClockBypass = SDIO_ClockBypass_Disable;
+ SDIO_InitStructure.SDIO_ClockPowerSave = SDIO_ClockPowerSave_Disable;
+ SDIO_InitStructure.SDIO_BusWide = SDIO_BusWide_1b;
+ SDIO_InitStructure.SDIO_HardwareFlowControl = SDIO_HardwareFlowControl_Disable;
+ SDIO_Init(&SDIO_InitStructure);
+
+ /* Set Power State to ON */
+ SDIO_SetPowerState(SDIO_PowerState_ON);
+
+ /* Enable SDIO Clock */
+ SDIO_ClockCmd(ENABLE);
+
+ /* CMD0: GO_IDLE_STATE -------------------------------------------------------*/
+ /* No CMD response required */
+ SDIO_CmdInitStructure.SDIO_Argument = 0x0;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_GO_IDLE_STATE;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_No;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdError();
+
+ if (errorstatus != SD_OK)
+ {
+ /* CMD Response TimeOut (wait for CMDSENT flag) */
+ return(errorstatus);
+ }
+
+ /* CMD8: SEND_IF_COND --------------------------------------------------------*/
+ /* Send CMD8 to verify SD card interface operating condition */
+ /* Argument: - [31:12]: Reserved (shall be set to '0')
+ - [11:8]: Supply Voltage (VHS) 0x1 (Range: 2.7-3.6 V)
+ - [7:0]: Check Pattern (recommended 0xAA) */
+ /* CMD Response: R7 */
+ SDIO_CmdInitStructure.SDIO_Argument = SD_CHECK_PATTERN;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SEND_IF_COND;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp7Error();
+
+ if (errorstatus == SD_OK)
+ {
+ SDType = SD_HIGH_CAPACITY; /* SD Card 2.0 */
+ }
+ else
+ {
+ /* CMD55 */
+ SDIO_CmdInitStructure.SDIO_Argument = 0x00;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_APP_CMD;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+ errorstatus = CmdResp1Error(SDIO_APP_CMD);
+ }
+ /* CMD55 */
+ SDIO_CmdInitStructure.SDIO_Argument = 0x00;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_APP_CMD;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+ errorstatus = CmdResp1Error(SDIO_APP_CMD);
+
+ /* If errorstatus is Command TimeOut, it is a MMC card */
+ /* If errorstatus is SD_OK it is a SD card: SD card 2.0 (voltage range mismatch)
+ or SD card 1.x */
+ if (errorstatus == SD_OK)
+ {
+ /* SD CARD */
+ /* Send ACMD41 SD_APP_OP_COND with Argument 0x80100000 */
+ while ((!validvoltage) && (count < SD_MAX_VOLT_TRIAL))
+ {
+
+ /* SEND CMD55 APP_CMD with RCA as 0 */
+ SDIO_CmdInitStructure.SDIO_Argument = 0x00;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_APP_CMD;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_APP_CMD);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+ SDIO_CmdInitStructure.SDIO_Argument = SD_VOLTAGE_WINDOW_SD | SDType;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SD_APP_OP_COND;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp3Error();
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ response = SDIO_GetResponse(SDIO_RESP1);
+ validvoltage = (bool) (((response >> 31) == 1) ? 1 : 0);
+ count++;
+ }
+ if (count >= SD_MAX_VOLT_TRIAL)
+ {
+ errorstatus = SD_INVALID_VOLTRANGE;
+ return(errorstatus);
+ }
+
+ if (SDType == SD_HIGH_CAPACITY)
+ {
+ CardType = SDIO_HIGH_CAPACITY_SD_CARD;
+ }
+ else
+ {
+ CardType = SDIO_SECURE_DIGITAL_CARD;
+ }
+ }/* else MMC Card */
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_PowerOFF
+* Description : Turns the SDIO output signals off.
+* Input : None
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_PowerOFF(void)
+{
+ SD_Error errorstatus = SD_OK;
+
+ /* Set Power State to OFF */
+ SDIO_SetPowerState(SDIO_PowerState_OFF);
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_InitializeCards
+* Description : Intialises all cards or single card as the case may be.
+* Card(s) come into standby state.
+* Input : None
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_InitializeCards(void)
+{
+ SD_Error errorstatus = SD_OK;
+ u16 rca = 0x01;
+
+ if (SDIO_GetPowerState() == SDIO_PowerState_OFF)
+ {
+ errorstatus = SD_REQUEST_NOT_APPLICABLE;
+ return(errorstatus);
+ }
+
+ if (SDIO_SECURE_DIGITAL_IO_CARD != CardType)
+ {
+ /* Send CMD2 ALL_SEND_CID */
+ SDIO_CmdInitStructure.SDIO_Argument = 0x0;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_ALL_SEND_CID;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Long;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp2Error();
+
+ if (SD_OK != errorstatus)
+ {
+ return(errorstatus);
+ }
+
+ CID_Tab[0] = SDIO_GetResponse(SDIO_RESP1);
+ CID_Tab[1] = SDIO_GetResponse(SDIO_RESP2);
+ CID_Tab[2] = SDIO_GetResponse(SDIO_RESP3);
+ CID_Tab[3] = SDIO_GetResponse(SDIO_RESP4);
+ }
+ if ((SDIO_SECURE_DIGITAL_CARD == CardType) || (SDIO_SECURE_DIGITAL_IO_CARD == CardType) || (SDIO_SECURE_DIGITAL_IO_COMBO_CARD == CardType)
+ || (SDIO_HIGH_CAPACITY_SD_CARD == CardType))
+ {
+ /* Send CMD3 SET_REL_ADDR with argument 0 */
+ /* SD Card publishes its RCA. */
+ SDIO_CmdInitStructure.SDIO_Argument = 0x00;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SET_REL_ADDR;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp6Error(SDIO_SET_REL_ADDR, &rca);
+
+ if (SD_OK != errorstatus)
+ {
+ return(errorstatus);
+ }
+ }
+
+ if (SDIO_SECURE_DIGITAL_IO_CARD != CardType)
+ {
+ RCA = rca;
+
+ /* Send CMD9 SEND_CSD with argument as card's RCA */
+ SDIO_CmdInitStructure.SDIO_Argument = (u32)(rca << 16);
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SEND_CSD;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Long;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp2Error();
+
+ if (SD_OK != errorstatus)
+ {
+ return(errorstatus);
+ }
+
+ CSD_Tab[0] = SDIO_GetResponse(SDIO_RESP1);
+ CSD_Tab[1] = SDIO_GetResponse(SDIO_RESP2);
+ CSD_Tab[2] = SDIO_GetResponse(SDIO_RESP3);
+ CSD_Tab[3] = SDIO_GetResponse(SDIO_RESP4);
+ }
+
+ errorstatus = SD_OK; /* All cards get intialized */
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_GetCardInfo
+* Description : Returns information about specific card.
+* Input : cardinfo : pointer to a SD_CardInfo structure
+* that contains all SD card information.
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_GetCardInfo(SD_CardInfo *cardinfo)
+{
+ SD_Error errorstatus = SD_OK;
+ u8 tmp = 0;
+
+ cardinfo->CardType = (u8)CardType;
+ cardinfo->RCA = (u16)RCA;
+
+ /* Byte 0 */
+ tmp = (u8)((CSD_Tab[0] & 0xFF000000) >> 24);
+ cardinfo->SD_csd.CSDStruct = (tmp & 0xC0) >> 6;
+ cardinfo->SD_csd.SysSpecVersion = (tmp & 0x3C) >> 2;
+ cardinfo->SD_csd.Reserved1 = tmp & 0x03;
+
+ /* Byte 1 */
+ tmp = (u8)((CSD_Tab[0] & 0x00FF0000) >> 16);
+ cardinfo->SD_csd.TAAC = tmp;
+
+ /* Byte 2 */
+ tmp = (u8)((CSD_Tab[0] & 0x0000FF00) >> 8);
+ cardinfo->SD_csd.NSAC = tmp;
+
+ /* Byte 3 */
+ tmp = (u8)(CSD_Tab[0] & 0x000000FF);
+ cardinfo->SD_csd.MaxBusClkFrec = tmp;
+
+ /* Byte 4 */
+ tmp = (u8)((CSD_Tab[1] & 0xFF000000) >> 24);
+ cardinfo->SD_csd.CardComdClasses = tmp << 4;
+
+ /* Byte 5 */
+ tmp = (u8)((CSD_Tab[1] & 0x00FF0000) >> 16);
+ cardinfo->SD_csd.CardComdClasses |= (tmp & 0xF0) >> 4;
+ cardinfo->SD_csd.RdBlockLen = tmp & 0x0F;
+
+ /* Byte 6 */
+ tmp = (u8)((CSD_Tab[1] & 0x0000FF00) >> 8);
+ cardinfo->SD_csd.PartBlockRead = (tmp & 0x80) >> 7;
+ cardinfo->SD_csd.WrBlockMisalign = (tmp & 0x40) >> 6;
+ cardinfo->SD_csd.RdBlockMisalign = (tmp & 0x20) >> 5;
+ cardinfo->SD_csd.DSRImpl = (tmp & 0x10) >> 4;
+ cardinfo->SD_csd.Reserved2 = 0; /* Reserved */
+ cardinfo->SD_csd.DeviceSize = (tmp & 0x03) << 10;
+
+ /* Byte 7 */
+ tmp = (u8)(CSD_Tab[1] & 0x000000FF);
+ cardinfo->SD_csd.DeviceSize |= (tmp) << 2;
+
+ /* Byte 8 */
+ tmp = (u8)((CSD_Tab[2] & 0xFF000000) >> 24);
+
+ cardinfo->SD_csd.DeviceSize |= (tmp & 0xC0) >> 6;
+ cardinfo->SD_csd.MaxRdCurrentVDDMin = (tmp & 0x38) >> 3;
+ cardinfo->SD_csd.MaxRdCurrentVDDMax = (tmp & 0x07);
+
+ /* Byte 9 */
+ tmp = (u8)((CSD_Tab[2] & 0x00FF0000) >> 16);
+ cardinfo->SD_csd.MaxWrCurrentVDDMin = (tmp & 0xE0) >> 5;
+ cardinfo->SD_csd.MaxWrCurrentVDDMax = (tmp & 0x1C) >> 2;
+ cardinfo->SD_csd.DeviceSizeMul = (tmp & 0x03) << 1;
+
+ /* Byte 10 */
+ tmp = (u8)((CSD_Tab[2] & 0x0000FF00) >> 8);
+ cardinfo->SD_csd.DeviceSizeMul |= (tmp & 0x80) >> 7;
+ cardinfo->SD_csd.EraseGrSize = (tmp & 0x40) >> 6;
+ cardinfo->SD_csd.EraseGrMul = (tmp & 0x3F) << 1;
+
+ /* Byte 11 */
+ tmp = (u8)(CSD_Tab[2] & 0x000000FF);
+ cardinfo->SD_csd.EraseGrMul |= (tmp & 0x80) >> 7;
+ cardinfo->SD_csd.WrProtectGrSize = (tmp & 0x7F);
+
+ /* Byte 12 */
+ tmp = (u8)((CSD_Tab[3] & 0xFF000000) >> 24);
+ cardinfo->SD_csd.WrProtectGrEnable = (tmp & 0x80) >> 7;
+ cardinfo->SD_csd.ManDeflECC = (tmp & 0x60) >> 5;
+ cardinfo->SD_csd.WrSpeedFact = (tmp & 0x1C) >> 2;
+ cardinfo->SD_csd.MaxWrBlockLen = (tmp & 0x03) << 2;
+
+ /* Byte 13 */
+ tmp = (u8)((CSD_Tab[3] & 0x00FF0000) >> 16);
+ cardinfo->SD_csd.MaxWrBlockLen |= (tmp & 0xC0) >> 6;
+ cardinfo->SD_csd.WriteBlockPaPartial = (tmp & 0x20) >> 5;
+ cardinfo->SD_csd.Reserved3 = 0;
+ cardinfo->SD_csd.ContentProtectAppli = (tmp & 0x01);
+
+ /* Byte 14 */
+ tmp = (u8)((CSD_Tab[3] & 0x0000FF00) >> 8);
+ cardinfo->SD_csd.FileFormatGrouop = (tmp & 0x80) >> 7;
+ cardinfo->SD_csd.CopyFlag = (tmp & 0x40) >> 6;
+ cardinfo->SD_csd.PermWrProtect = (tmp & 0x20) >> 5;
+ cardinfo->SD_csd.TempWrProtect = (tmp & 0x10) >> 4;
+ cardinfo->SD_csd.FileFormat = (tmp & 0x0C) >> 2;
+ cardinfo->SD_csd.ECC = (tmp & 0x03);
+
+ /* Byte 15 */
+ tmp = (u8)(CSD_Tab[3] & 0x000000FF);
+ cardinfo->SD_csd.CSD_CRC = (tmp & 0xFE) >> 1;
+ cardinfo->SD_csd.Reserved4 = 1;
+
+
+ /* Byte 0 */
+ tmp = (u8)((CID_Tab[0] & 0xFF000000) >> 24);
+ cardinfo->SD_cid.ManufacturerID = tmp;
+
+ /* Byte 1 */
+ tmp = (u8)((CID_Tab[0] & 0x00FF0000) >> 16);
+ cardinfo->SD_cid.OEM_AppliID = tmp << 8;
+
+ /* Byte 2 */
+ tmp = (u8)((CID_Tab[0] & 0x000000FF00) >> 8);
+ cardinfo->SD_cid.OEM_AppliID |= tmp;
+
+ /* Byte 3 */
+ tmp = (u8)(CID_Tab[0] & 0x000000FF);
+ cardinfo->SD_cid.ProdName1 = tmp << 24;
+
+ /* Byte 4 */
+ tmp = (u8)((CID_Tab[1] & 0xFF000000) >> 24);
+ cardinfo->SD_cid.ProdName1 |= tmp << 16;
+
+ /* Byte 5 */
+ tmp = (u8)((CID_Tab[1] & 0x00FF0000) >> 16);
+ cardinfo->SD_cid.ProdName1 |= tmp << 8;
+
+ /* Byte 6 */
+ tmp = (u8)((CID_Tab[1] & 0x0000FF00) >> 8);
+ cardinfo->SD_cid.ProdName1 |= tmp;
+
+ /* Byte 7 */
+ tmp = (u8)(CID_Tab[1] & 0x000000FF);
+ cardinfo->SD_cid.ProdName2 = tmp;
+
+ /* Byte 8 */
+ tmp = (u8)((CID_Tab[2] & 0xFF000000) >> 24);
+ cardinfo->SD_cid.ProdRev = tmp;
+
+ /* Byte 9 */
+ tmp = (u8)((CID_Tab[2] & 0x00FF0000) >> 16);
+ cardinfo->SD_cid.ProdSN = tmp << 24;
+
+ /* Byte 10 */
+ tmp = (u8)((CID_Tab[2] & 0x0000FF00) >> 8);
+ cardinfo->SD_cid.ProdSN |= tmp << 16;
+
+ /* Byte 11 */
+ tmp = (u8)(CID_Tab[2] & 0x000000FF);
+ cardinfo->SD_cid.ProdSN |= tmp << 8;
+
+ /* Byte 12 */
+ tmp = (u8)((CID_Tab[3] & 0xFF000000) >> 24);
+ cardinfo->SD_cid.ProdSN |= tmp;
+
+ /* Byte 13 */
+ tmp = (u8)((CID_Tab[3] & 0x00FF0000) >> 16);
+ cardinfo->SD_cid.Reserved1 |= (tmp & 0xF0) >> 4;
+ cardinfo->SD_cid.ManufactDate = (tmp & 0x0F) << 8;
+
+ /* Byte 14 */
+ tmp = (u8)((CID_Tab[3] & 0x0000FF00) >> 8);
+ cardinfo->SD_cid.ManufactDate |= tmp;
+
+ /* Byte 15 */
+ tmp = (u8)(CID_Tab[3] & 0x000000FF);
+ cardinfo->SD_cid.CID_CRC = (tmp & 0xFE) >> 1;
+ cardinfo->SD_cid.Reserved2 = 1;
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_EnableWideBusOperation
+* Description : Enables wide bus opeartion for the requeseted card if
+* supported by card.
+* Input : WideMode: Specifies the SD card wide bus mode.
+* This parameter can be one of the following values:
+* - SDIO_BusWide_8b: 8-bit data transfer (Only for MMC)
+* - SDIO_BusWide_4b: 4-bit data transfer
+* - SDIO_BusWide_1b: 1-bit data transfer
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_EnableWideBusOperation(u32 WideMode)
+{
+ SD_Error errorstatus = SD_OK;
+
+ /* MMC Card doesn't support this feature */
+ if (SDIO_MULTIMEDIA_CARD == CardType)
+ {
+ errorstatus = SD_UNSUPPORTED_FEATURE;
+ return(errorstatus);
+ }
+ else if ((SDIO_SECURE_DIGITAL_CARD == CardType) || (SDIO_HIGH_CAPACITY_SD_CARD == CardType))
+ {
+ if (SDIO_BusWide_8b == WideMode)
+ {
+ errorstatus = SD_UNSUPPORTED_FEATURE;
+ return(errorstatus);
+ }
+ else if (SDIO_BusWide_4b == WideMode)
+ {
+ errorstatus = SDEnWideBus(ENABLE);
+
+ if (SD_OK == errorstatus)
+ {
+ /* Configure the SDIO peripheral */
+ SDIO_InitStructure.SDIO_ClockDiv = SDIO_TRANSFER_CLK_DIV;
+ SDIO_InitStructure.SDIO_ClockEdge = SDIO_ClockEdge_Rising;
+ SDIO_InitStructure.SDIO_ClockBypass = SDIO_ClockBypass_Disable;
+ SDIO_InitStructure.SDIO_ClockPowerSave = SDIO_ClockPowerSave_Disable;
+ SDIO_InitStructure.SDIO_BusWide = SDIO_BusWide_4b;
+ SDIO_InitStructure.SDIO_HardwareFlowControl = SDIO_HardwareFlowControl_Disable;
+ SDIO_Init(&SDIO_InitStructure);
+ }
+ }
+ else
+ {
+ errorstatus = SDEnWideBus(DISABLE);
+
+ if (SD_OK == errorstatus)
+ {
+ /* Configure the SDIO peripheral */
+ SDIO_InitStructure.SDIO_ClockDiv = SDIO_TRANSFER_CLK_DIV;
+ SDIO_InitStructure.SDIO_ClockEdge = SDIO_ClockEdge_Rising;
+ SDIO_InitStructure.SDIO_ClockBypass = SDIO_ClockBypass_Disable;
+ SDIO_InitStructure.SDIO_ClockPowerSave = SDIO_ClockPowerSave_Disable;
+ SDIO_InitStructure.SDIO_BusWide = SDIO_BusWide_1b;
+ SDIO_InitStructure.SDIO_HardwareFlowControl = SDIO_HardwareFlowControl_Disable;
+ SDIO_Init(&SDIO_InitStructure);
+ }
+ }
+ }
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_SetDeviceMode
+* Description : Sets device mode whether to operate in Polling, Interrupt or
+* DMA mode.
+* Input : Mode: Specifies the Data Transfer mode.
+* This parameter can be one of the following values:
+* - SD_DMA_MODE: Data transfer using DMA.
+* - SD_INTERRUPT_MODE: Data transfer using interrupts.
+* - SD_POLLING_MODE: Data transfer using flags.
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_SetDeviceMode(u32 Mode)
+{
+ SD_Error errorstatus = SD_OK;
+
+ if ((Mode == SD_DMA_MODE) || (Mode == SD_INTERRUPT_MODE) || (Mode == SD_POLLING_MODE))
+ {
+ DeviceMode = Mode;
+ }
+ else
+ {
+ errorstatus = SD_INVALID_PARAMETER;
+ }
+ return(errorstatus);
+
+}
+
+/*******************************************************************************
+* Function Name : SD_SelectDeselect
+* Description : Selects od Deselects the corresponding card.
+* Input : addr: Address of the Card to be selected.
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_SelectDeselect(u32 addr)
+{
+ SD_Error errorstatus = SD_OK;
+
+ /* Send CMD7 SDIO_SEL_DESEL_CARD */
+ SDIO_CmdInitStructure.SDIO_Argument = addr;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SEL_DESEL_CARD;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_SEL_DESEL_CARD);
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_ReadBlock
+* Description : Allows to read one block from a specified address in a card.
+* Input : - addr: Address from where data are to be read.
+* - readbuff: pointer to the buffer that will contain the
+* received data
+* - blocksize: the SD card Data block size.
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_ReadBlock(u32 addr, u32 *readbuff, u16 BlockSize)
+{
+ SD_Error errorstatus = SD_OK;
+ u32 count = 0, *tempbuff = readbuff;
+ u8 power = 0;
+
+ if (NULL == readbuff)
+ {
+ errorstatus = SD_INVALID_PARAMETER;
+ return(errorstatus);
+ }
+
+ TransferError = SD_OK;
+ TransferEnd = 0;
+ TotalNumberOfBytes = 0;
+
+ /* Clear all DPSM configuration */
+ SDIO_DataInitStructure.SDIO_DataTimeOut = SD_DATATIMEOUT;
+ SDIO_DataInitStructure.SDIO_DataLength = 0;
+ SDIO_DataInitStructure.SDIO_DataBlockSize = SDIO_DataBlockSize_1b;
+ SDIO_DataInitStructure.SDIO_TransferDir = SDIO_TransferDir_ToCard;
+ SDIO_DataInitStructure.SDIO_TransferMode = SDIO_TransferMode_Block;
+ SDIO_DataInitStructure.SDIO_DPSM = SDIO_DPSM_Disable;
+ SDIO_DataConfig(&SDIO_DataInitStructure);
+ SDIO_DMACmd(DISABLE);
+
+ if (SDIO_GetResponse(SDIO_RESP1) & SD_CARD_LOCKED)
+ {
+ errorstatus = SD_LOCK_UNLOCK_FAILED;
+ return(errorstatus);
+ }
+
+ if ((BlockSize > 0) && (BlockSize <= 2048) && ((BlockSize & (BlockSize - 1)) == 0))
+ {
+ power = convert_from_bytes_to_power_of_two(BlockSize);
+
+ /* Set Block Size for Card */
+ SDIO_CmdInitStructure.SDIO_Argument = (u32) BlockSize;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SET_BLOCKLEN;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_SET_BLOCKLEN);
+
+ if (SD_OK != errorstatus)
+ {
+ return(errorstatus);
+ }
+ }
+ else
+ {
+ errorstatus = SD_INVALID_PARAMETER;
+ return(errorstatus);
+ }
+
+ SDIO_DataInitStructure.SDIO_DataTimeOut = SD_DATATIMEOUT;
+ SDIO_DataInitStructure.SDIO_DataLength = BlockSize;
+ SDIO_DataInitStructure.SDIO_DataBlockSize = (u32) power << 4;
+ SDIO_DataInitStructure.SDIO_TransferDir = SDIO_TransferDir_ToSDIO;
+ SDIO_DataInitStructure.SDIO_TransferMode = SDIO_TransferMode_Block;
+ SDIO_DataInitStructure.SDIO_DPSM = SDIO_DPSM_Enable;
+ SDIO_DataConfig(&SDIO_DataInitStructure);
+
+ TotalNumberOfBytes = BlockSize;
+ StopCondition = 0;
+ DestBuffer = readbuff;
+
+ /* Send CMD17 READ_SINGLE_BLOCK */
+ SDIO_CmdInitStructure.SDIO_Argument = (u32)addr;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_READ_SINGLE_BLOCK;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_READ_SINGLE_BLOCK);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+ /* In case of single block transfer, no need of stop transfer at all.*/
+ if (DeviceMode == SD_POLLING_MODE)
+ {
+ /* Polling mode */
+ while (!(SDIO->STA &(SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DBCKEND | SDIO_FLAG_STBITERR)))
+ {
+ if (SDIO_GetFlagStatus(SDIO_FLAG_RXFIFOHF) != RESET)
+ {
+ for (count = 0; count < 8; count++)
+ {
+ *(tempbuff + count) = SDIO_ReadData();
+ }
+ tempbuff += 8;
+ }
+ }
+
+ if (SDIO_GetFlagStatus(SDIO_FLAG_DTIMEOUT) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_DTIMEOUT);
+ errorstatus = SD_DATA_TIMEOUT;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_DCRCFAIL) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_DCRCFAIL);
+ errorstatus = SD_DATA_CRC_FAIL;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_RXOVERR) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_RXOVERR);
+ errorstatus = SD_RX_OVERRUN;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_STBITERR) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_STBITERR);
+ errorstatus = SD_START_BIT_ERR;
+ return(errorstatus);
+ }
+ while (SDIO_GetFlagStatus(SDIO_FLAG_RXDAVL) != RESET)
+ {
+ *tempbuff = SDIO_ReadData();
+ tempbuff++;
+ }
+
+ /* Clear all the static flags */
+ SDIO_ClearFlag(SDIO_STATIC_FLAGS);
+ }
+ else if (DeviceMode == SD_INTERRUPT_MODE)
+ {
+ SDIO_ITConfig(SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_DATAEND | SDIO_IT_RXOVERR | SDIO_IT_RXFIFOHF | SDIO_IT_STBITERR, ENABLE);
+ while ((TransferEnd == 0) && (TransferError == SD_OK))
+ {}
+ if (TransferError != SD_OK)
+ {
+ return(TransferError);
+ }
+ }
+ else if (DeviceMode == SD_DMA_MODE)
+ {
+ SDIO_ITConfig(SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_DATAEND | SDIO_IT_RXOVERR | SDIO_IT_STBITERR, ENABLE);
+ SDIO_DMACmd(ENABLE);
+ DMA_RxConfiguration(readbuff, BlockSize);
+ while (DMA_GetFlagStatus(DMA2_FLAG_TC4) == RESET)
+ {}
+ }
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_ReadMultiBlocks
+* Description : Allows to read blocks from a specified address in a card.
+* Input : - addr: Address from where data are to be read.
+* - readbuff: pointer to the buffer that will contain the
+* received data.
+* - BlockSize: the SD card Data block size.
+* - NumberOfBlocks: number of blocks to be read.
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_ReadMultiBlocks(u32 addr, u32 *readbuff, u16 BlockSize, u32 NumberOfBlocks)
+{
+ SD_Error errorstatus = SD_OK;
+ u32 count = 0, *tempbuff = readbuff;
+ u8 power = 0;
+
+ if (NULL == readbuff)
+ {
+ errorstatus = SD_INVALID_PARAMETER;
+ return(errorstatus);
+ }
+
+ TransferError = SD_OK;
+ TransferEnd = 0;
+ TotalNumberOfBytes = 0;
+
+ /* Clear all DPSM configuration */
+ SDIO_DataInitStructure.SDIO_DataTimeOut = SD_DATATIMEOUT;
+ SDIO_DataInitStructure.SDIO_DataLength = 0;
+ SDIO_DataInitStructure.SDIO_DataBlockSize = SDIO_DataBlockSize_1b;
+ SDIO_DataInitStructure.SDIO_TransferDir = SDIO_TransferDir_ToCard;
+ SDIO_DataInitStructure.SDIO_TransferMode = SDIO_TransferMode_Block;
+ SDIO_DataInitStructure.SDIO_DPSM = SDIO_DPSM_Disable;
+ SDIO_DataConfig(&SDIO_DataInitStructure);
+ SDIO_DMACmd(DISABLE);
+
+ if (SDIO_GetResponse(SDIO_RESP1) & SD_CARD_LOCKED)
+ {
+ errorstatus = SD_LOCK_UNLOCK_FAILED;
+ return(errorstatus);
+ }
+
+ if ((BlockSize > 0) && (BlockSize <= 2048) && (0 == (BlockSize & (BlockSize - 1))))
+ {
+ power = convert_from_bytes_to_power_of_two(BlockSize);
+
+ /* Set Block Size for Card */
+ SDIO_CmdInitStructure.SDIO_Argument = (u32) BlockSize;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SET_BLOCKLEN;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_SET_BLOCKLEN);
+
+ if (SD_OK != errorstatus)
+ {
+ return(errorstatus);
+ }
+ }
+ else
+ {
+ errorstatus = SD_INVALID_PARAMETER;
+ return(errorstatus);
+ }
+
+ if (NumberOfBlocks > 1)
+ {
+ /* Common to all modes */
+ if (NumberOfBlocks * BlockSize > SD_MAX_DATA_LENGTH)
+ {
+ errorstatus = SD_INVALID_PARAMETER;
+ return(errorstatus);
+ }
+
+ TotalNumberOfBytes = NumberOfBlocks * BlockSize;
+ StopCondition = 1;
+ DestBuffer = readbuff;
+
+ SDIO_DataInitStructure.SDIO_DataTimeOut = SD_DATATIMEOUT;
+ SDIO_DataInitStructure.SDIO_DataLength = NumberOfBlocks * BlockSize;
+ SDIO_DataInitStructure.SDIO_DataBlockSize = (u32) power << 4;
+ SDIO_DataInitStructure.SDIO_TransferDir = SDIO_TransferDir_ToSDIO;
+ SDIO_DataInitStructure.SDIO_TransferMode = SDIO_TransferMode_Block;
+ SDIO_DataInitStructure.SDIO_DPSM = SDIO_DPSM_Enable;
+ SDIO_DataConfig(&SDIO_DataInitStructure);
+
+ /* Send CMD18 READ_MULT_BLOCK with argument data address */
+ SDIO_CmdInitStructure.SDIO_Argument = (u32)addr;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_READ_MULT_BLOCK;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_READ_MULT_BLOCK);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ if (DeviceMode == SD_POLLING_MODE)
+ {
+ /* Polling mode */
+ while (!(SDIO->STA &(SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DATAEND | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_STBITERR)))
+ {
+ if (SDIO_GetFlagStatus(SDIO_FLAG_RXFIFOHF) != RESET)
+ {
+ for (count = 0; count < SD_HALFFIFO; count++)
+ {
+ *(tempbuff + count) = SDIO_ReadData();
+ }
+ tempbuff += SD_HALFFIFO;
+ }
+ }
+
+ if (SDIO_GetFlagStatus(SDIO_FLAG_DTIMEOUT) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_DTIMEOUT);
+ errorstatus = SD_DATA_TIMEOUT;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_DCRCFAIL) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_DCRCFAIL);
+ errorstatus = SD_DATA_CRC_FAIL;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_RXOVERR) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_RXOVERR);
+ errorstatus = SD_RX_OVERRUN;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_STBITERR) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_STBITERR);
+ errorstatus = SD_START_BIT_ERR;
+ return(errorstatus);
+ }
+ while (SDIO_GetFlagStatus(SDIO_FLAG_RXDAVL) != RESET)
+ {
+ *tempbuff = SDIO_ReadData();
+ tempbuff++;
+ }
+
+ if (SDIO_GetFlagStatus(SDIO_FLAG_DATAEND) != RESET)
+ {
+ /* In Case Of SD-CARD Send Command STOP_TRANSMISSION */
+ if ((SDIO_SECURE_DIGITAL_CARD == CardType) || (SDIO_HIGH_CAPACITY_SD_CARD == CardType))
+ {
+ /* Send CMD12 STOP_TRANSMISSION */
+ SDIO_CmdInitStructure.SDIO_Argument = 0x0;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_STOP_TRANSMISSION;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_STOP_TRANSMISSION);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+ }
+ }
+ /* Clear all the static flags */
+ SDIO_ClearFlag(SDIO_STATIC_FLAGS);
+ }
+ else if (DeviceMode == SD_INTERRUPT_MODE)
+ {
+ SDIO_ITConfig(SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_DATAEND | SDIO_IT_RXOVERR | SDIO_IT_RXFIFOHF | SDIO_IT_STBITERR, ENABLE);
+ while ((TransferEnd == 0) && (TransferError == SD_OK))
+ {}
+ if (TransferError != SD_OK)
+ {
+ return(TransferError);
+ }
+ }
+ else if (DeviceMode == SD_DMA_MODE)
+ {
+ SDIO_ITConfig(SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_DATAEND | SDIO_IT_RXOVERR | SDIO_IT_STBITERR, ENABLE);
+ SDIO_DMACmd(ENABLE);
+ DMA_RxConfiguration(readbuff, (NumberOfBlocks * BlockSize));
+ while (DMA_GetFlagStatus(DMA2_FLAG_TC4) == RESET)
+ {}
+ while ((TransferEnd == 0) && (TransferError == SD_OK))
+ {}
+ if (TransferError != SD_OK)
+ {
+ return(TransferError);
+ }
+ }
+ }
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_WriteBlock
+* Description : Allows to write one block starting from a specified address
+* in a card.
+* Input : - addr: Address from where data are to be read.
+* - writebuff: pointer to the buffer that contain the data to be
+* transferred.
+* - BlockSize: the SD card Data block size.
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_WriteBlock(u32 addr, u32 *writebuff, u16 BlockSize)
+{
+ SD_Error errorstatus = SD_OK;
+ u8 power = 0, cardstate = 0;
+ u32 timeout = 0, bytestransferred = 0;
+ u32 cardstatus = 0, count = 0, restwords = 0;
+ u32 *tempbuff = writebuff;
+
+ if (writebuff == NULL)
+ {
+ errorstatus = SD_INVALID_PARAMETER;
+ return(errorstatus);
+ }
+
+ TransferError = SD_OK;
+ TransferEnd = 0;
+ TotalNumberOfBytes = 0;
+
+ SDIO_DataInitStructure.SDIO_DataTimeOut = SD_DATATIMEOUT;
+ SDIO_DataInitStructure.SDIO_DataLength = 0;
+ SDIO_DataInitStructure.SDIO_DataBlockSize = SDIO_DataBlockSize_1b;
+ SDIO_DataInitStructure.SDIO_TransferDir = SDIO_TransferDir_ToCard;
+ SDIO_DataInitStructure.SDIO_TransferMode = SDIO_TransferMode_Block;
+ SDIO_DataInitStructure.SDIO_DPSM = SDIO_DPSM_Disable;
+ SDIO_DataConfig(&SDIO_DataInitStructure);
+ SDIO_DMACmd(DISABLE);
+
+ if (SDIO_GetResponse(SDIO_RESP1) & SD_CARD_LOCKED)
+ {
+ errorstatus = SD_LOCK_UNLOCK_FAILED;
+ return(errorstatus);
+ }
+
+ /* Set the block size, both on controller and card */
+ if ((BlockSize > 0) && (BlockSize <= 2048) && ((BlockSize & (BlockSize - 1)) == 0))
+ {
+ power = convert_from_bytes_to_power_of_two(BlockSize);
+
+ SDIO_CmdInitStructure.SDIO_Argument = (u32) BlockSize;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SET_BLOCKLEN;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_SET_BLOCKLEN);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+ }
+ else
+ {
+ errorstatus = SD_INVALID_PARAMETER;
+ return(errorstatus);
+ }
+
+ /* Wait till card is ready for data Added */
+ SDIO_CmdInitStructure.SDIO_Argument = (u32) (RCA << 16);
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SEND_STATUS;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_SEND_STATUS);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ cardstatus = SDIO_GetResponse(SDIO_RESP1);
+
+ timeout = SD_DATATIMEOUT;
+
+ while (((cardstatus & 0x00000100) == 0) && (timeout > 0))
+ {
+ timeout--;
+ SDIO_CmdInitStructure.SDIO_Argument = (u32) (RCA << 16);
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SEND_STATUS;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_SEND_STATUS);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+ cardstatus = SDIO_GetResponse(SDIO_RESP1);
+ }
+
+ if (timeout == 0)
+ {
+ return(SD_ERROR);
+ }
+
+ /* Send CMD24 WRITE_SINGLE_BLOCK */
+ SDIO_CmdInitStructure.SDIO_Argument = addr;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_WRITE_SINGLE_BLOCK;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_WRITE_SINGLE_BLOCK);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ TotalNumberOfBytes = BlockSize;
+ StopCondition = 0;
+ SrcBuffer = writebuff;
+
+ SDIO_DataInitStructure.SDIO_DataTimeOut = SD_DATATIMEOUT;
+ SDIO_DataInitStructure.SDIO_DataLength = BlockSize;
+ SDIO_DataInitStructure.SDIO_DataBlockSize = (u32) power << 4;
+ SDIO_DataInitStructure.SDIO_TransferDir = SDIO_TransferDir_ToCard;
+ SDIO_DataInitStructure.SDIO_TransferMode = SDIO_TransferMode_Block;
+ SDIO_DataInitStructure.SDIO_DPSM = SDIO_DPSM_Enable;
+ SDIO_DataConfig(&SDIO_DataInitStructure);
+
+ /* In case of single data block transfer no need of stop command at all */
+ if (DeviceMode == SD_POLLING_MODE)
+ {
+ while (!(SDIO->STA & (SDIO_FLAG_DBCKEND | SDIO_FLAG_TXUNDERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_STBITERR)))
+ {
+ if (SDIO_GetFlagStatus(SDIO_FLAG_TXFIFOHE) != RESET)
+ {
+ if ((TotalNumberOfBytes - bytestransferred) < 32)
+ {
+ restwords = ((TotalNumberOfBytes - bytestransferred) % 4 == 0) ? ((TotalNumberOfBytes - bytestransferred) / 4) : (( TotalNumberOfBytes - bytestransferred) / 4 + 1);
+
+ for (count = 0; count < restwords; count++, tempbuff++, bytestransferred += 4)
+ {
+ SDIO_WriteData(*tempbuff);
+ }
+ }
+ else
+ {
+ for (count = 0; count < 8; count++)
+ {
+ SDIO_WriteData(*(tempbuff + count));
+ }
+ tempbuff += 8;
+ bytestransferred += 32;
+ }
+ }
+ }
+ if (SDIO_GetFlagStatus(SDIO_FLAG_DTIMEOUT) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_DTIMEOUT);
+ errorstatus = SD_DATA_TIMEOUT;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_DCRCFAIL) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_DCRCFAIL);
+ errorstatus = SD_DATA_CRC_FAIL;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_TXUNDERR) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_TXUNDERR);
+ errorstatus = SD_TX_UNDERRUN;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_STBITERR) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_STBITERR);
+ errorstatus = SD_START_BIT_ERR;
+ return(errorstatus);
+ }
+ }
+ else if (DeviceMode == SD_INTERRUPT_MODE)
+ {
+ SDIO_ITConfig(SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_DATAEND | SDIO_FLAG_TXFIFOHE | SDIO_IT_TXUNDERR | SDIO_IT_STBITERR, ENABLE);
+ while ((TransferEnd == 0) && (TransferError == SD_OK))
+ {}
+ if (TransferError != SD_OK)
+ {
+ return(TransferError);
+ }
+ }
+ else if (DeviceMode == SD_DMA_MODE)
+ {
+ SDIO_ITConfig(SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_DATAEND | SDIO_IT_TXUNDERR | SDIO_IT_STBITERR, ENABLE);
+ DMA_TxConfiguration(writebuff, BlockSize);
+ SDIO_DMACmd(ENABLE);
+ while (DMA_GetFlagStatus(DMA2_FLAG_TC4) == RESET)
+ {}
+ while ((TransferEnd == 0) && (TransferError == SD_OK))
+ {}
+ if (TransferError != SD_OK)
+ {
+ return(TransferError);
+ }
+ }
+
+ /* Clear all the static flags */
+ SDIO_ClearFlag(SDIO_STATIC_FLAGS);
+
+ /* Wait till the card is in programming state */
+ errorstatus = IsCardProgramming(&cardstate);
+
+ while ((errorstatus == SD_OK) && ((cardstate == SD_CARD_PROGRAMMING) || (cardstate == SD_CARD_RECEIVING)))
+ {
+ errorstatus = IsCardProgramming(&cardstate);
+ }
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_WriteMultiBlocks
+* Description : Allows to write blocks starting from a specified address in
+* a card.
+* Input : - addr: Address from where data are to be read.
+* - writebuff: pointer to the buffer that contain the data to be
+* transferred.
+* - BlockSize: the SD card Data block size.
+* - NumberOfBlocks: number of blocks to be written.
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_WriteMultiBlocks(u32 addr, u32 *writebuff, u16 BlockSize, u32 NumberOfBlocks)
+{
+ SD_Error errorstatus = SD_OK;
+ u8 power = 0, cardstate = 0;
+ u32 bytestransferred = 0;
+ u32 count = 0, restwords = 0;
+ u32 *tempbuff = writebuff;
+
+ if (writebuff == NULL)
+ {
+ errorstatus = SD_INVALID_PARAMETER;
+ return(errorstatus);
+ }
+
+ TransferError = SD_OK;
+ TransferEnd = 0;
+ TotalNumberOfBytes = 0;
+
+ SDIO_DataInitStructure.SDIO_DataTimeOut = SD_DATATIMEOUT;
+ SDIO_DataInitStructure.SDIO_DataLength = 0;
+ SDIO_DataInitStructure.SDIO_DataBlockSize = SDIO_DataBlockSize_1b;
+ SDIO_DataInitStructure.SDIO_TransferDir = SDIO_TransferDir_ToCard;
+ SDIO_DataInitStructure.SDIO_TransferMode = SDIO_TransferMode_Block;
+ SDIO_DataInitStructure.SDIO_DPSM = SDIO_DPSM_Disable;
+ SDIO_DataConfig(&SDIO_DataInitStructure);
+ SDIO_DMACmd(DISABLE);
+
+ if (SDIO_GetResponse(SDIO_RESP1) & SD_CARD_LOCKED)
+ {
+ errorstatus = SD_LOCK_UNLOCK_FAILED;
+ return(errorstatus);
+ }
+
+ /* Set the block size, both on controller and card */
+ if ((BlockSize > 0) && (BlockSize <= 2048) && ((BlockSize & (BlockSize - 1)) == 0))
+ {
+ power = convert_from_bytes_to_power_of_two(BlockSize);
+
+ SDIO_CmdInitStructure.SDIO_Argument = (u32) BlockSize;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SET_BLOCKLEN;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_SET_BLOCKLEN);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+ }
+ else
+ {
+ errorstatus = SD_INVALID_PARAMETER;
+ return(errorstatus);
+ }
+
+ /* Wait till card is ready for data Added */
+ SDIO_CmdInitStructure.SDIO_Argument = (u32) (RCA << 16);
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SEND_STATUS;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_SEND_STATUS);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ if (NumberOfBlocks > 1)
+ {
+ /* Common to all modes */
+ if (NumberOfBlocks * BlockSize > SD_MAX_DATA_LENGTH)
+ {
+ errorstatus = SD_INVALID_PARAMETER;
+ return(errorstatus);
+ }
+
+ if ((SDIO_SECURE_DIGITAL_CARD == CardType) || (SDIO_HIGH_CAPACITY_SD_CARD == CardType))
+ {
+ /* To improve performance */
+ SDIO_CmdInitStructure.SDIO_Argument = (u32) (RCA << 16);
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_APP_CMD;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+
+ errorstatus = CmdResp1Error(SDIO_APP_CMD);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+ /* To improve performance */
+ SDIO_CmdInitStructure.SDIO_Argument = (u32)NumberOfBlocks;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SET_BLOCK_COUNT;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_SET_BLOCK_COUNT);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+ }
+
+ /* Send CMD25 WRITE_MULT_BLOCK with argument data address */
+ SDIO_CmdInitStructure.SDIO_Argument = (u32)addr;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_WRITE_MULT_BLOCK;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_WRITE_MULT_BLOCK);
+
+ if (SD_OK != errorstatus)
+ {
+ return(errorstatus);
+ }
+
+ TotalNumberOfBytes = NumberOfBlocks * BlockSize;
+ StopCondition = 1;
+ SrcBuffer = writebuff;
+
+ SDIO_DataInitStructure.SDIO_DataTimeOut = SD_DATATIMEOUT;
+ SDIO_DataInitStructure.SDIO_DataLength = NumberOfBlocks * BlockSize;
+ SDIO_DataInitStructure.SDIO_DataBlockSize = (u32) power << 4;
+ SDIO_DataInitStructure.SDIO_TransferDir = SDIO_TransferDir_ToCard;
+ SDIO_DataInitStructure.SDIO_TransferMode = SDIO_TransferMode_Block;
+ SDIO_DataInitStructure.SDIO_DPSM = SDIO_DPSM_Enable;
+ SDIO_DataConfig(&SDIO_DataInitStructure);
+
+ if (DeviceMode == SD_POLLING_MODE)
+ {
+ while (!(SDIO->STA & (SDIO_FLAG_TXUNDERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DATAEND | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_STBITERR)))
+ {
+ if (SDIO_GetFlagStatus(SDIO_FLAG_TXFIFOHE) != RESET)
+ {
+ if (!((TotalNumberOfBytes - bytestransferred) < SD_HALFFIFOBYTES))
+ {
+ for (count = 0; count < SD_HALFFIFO; count++)
+ {
+ SDIO_WriteData(*(tempbuff + count));
+ }
+ tempbuff += SD_HALFFIFO;
+ bytestransferred += SD_HALFFIFOBYTES;
+ }
+ else
+ {
+ restwords = ((TotalNumberOfBytes - bytestransferred) % 4 == 0) ? ((TotalNumberOfBytes - bytestransferred) / 4) :
+ ((TotalNumberOfBytes - bytestransferred) / 4 + 1);
+
+ for (count = 0; count < restwords; count++, tempbuff++, bytestransferred += 4)
+ {
+ SDIO_WriteData(*tempbuff);
+ }
+ }
+ }
+ }
+
+ if (SDIO_GetFlagStatus(SDIO_FLAG_DTIMEOUT) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_DTIMEOUT);
+ errorstatus = SD_DATA_TIMEOUT;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_DCRCFAIL) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_DCRCFAIL);
+ errorstatus = SD_DATA_CRC_FAIL;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_TXUNDERR) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_TXUNDERR);
+ errorstatus = SD_TX_UNDERRUN;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_STBITERR) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_STBITERR);
+ errorstatus = SD_START_BIT_ERR;
+ return(errorstatus);
+ }
+
+ if (SDIO_GetFlagStatus(SDIO_FLAG_DATAEND) != RESET)
+ {
+ if ((SDIO_SECURE_DIGITAL_CARD == CardType) || (SDIO_HIGH_CAPACITY_SD_CARD == CardType))
+ {
+ /* Send CMD12 STOP_TRANSMISSION */
+ SDIO_CmdInitStructure.SDIO_Argument = 0x0;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_STOP_TRANSMISSION;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+
+ errorstatus = CmdResp1Error(SDIO_STOP_TRANSMISSION);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+ }
+ }
+ }
+ else if (DeviceMode == SD_INTERRUPT_MODE)
+ {
+ SDIO_ITConfig(SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_DATAEND | SDIO_IT_TXFIFOHE | SDIO_IT_TXUNDERR | SDIO_IT_STBITERR, ENABLE);
+ while ((TransferEnd == 0) && (TransferError == SD_OK))
+ {}
+ if (TransferError != SD_OK)
+ {
+ return(TransferError);
+ }
+ }
+ else if (DeviceMode == SD_DMA_MODE)
+ {
+ SDIO_ITConfig(SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_DATAEND | SDIO_IT_TXUNDERR | SDIO_IT_STBITERR, ENABLE);
+ SDIO_DMACmd(ENABLE);
+ DMA_TxConfiguration(writebuff, (NumberOfBlocks * BlockSize));
+ while (DMA_GetFlagStatus(DMA2_FLAG_TC4) == RESET)
+ {}
+ while ((TransferEnd == 0) && (TransferError == SD_OK))
+ {}
+ if (TransferError != SD_OK)
+ {
+ return(TransferError);
+ }
+ }
+ }
+ /* Clear all the static flags */
+ SDIO_ClearFlag(SDIO_STATIC_FLAGS);
+
+ /* Wait till the card is in programming state */
+ errorstatus = IsCardProgramming(&cardstate);
+
+ while ((errorstatus == SD_OK) && ((cardstate == SD_CARD_PROGRAMMING) || (cardstate == SD_CARD_RECEIVING)))
+ {
+ errorstatus = IsCardProgramming(&cardstate);
+ }
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_GetTransferState
+* Description : Gets the cuurent data transfer state.
+* Input : None
+* Output : None
+* Return : SDTransferState: Data Transfer state.
+* This value can be:
+* - SD_NO_TRANSFER: No data transfer is acting
+* - SD_TRANSFER_IN_PROGRESS: Data transfer is acting
+*******************************************************************************/
+SDTransferState SD_GetTransferState(void)
+{
+ if (SDIO->STA & (SDIO_FLAG_TXACT | SDIO_FLAG_RXACT))
+ {
+ return(SD_TRANSFER_IN_PROGRESS);
+ }
+ else
+ {
+ return(SD_NO_TRANSFER);
+ }
+}
+
+/*******************************************************************************
+* Function Name : SD_StopTransfer
+* Description : Aborts an ongoing data transfer.
+* Input : None
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_StopTransfer(void)
+{
+ SD_Error errorstatus = SD_OK;
+
+ /* Send CMD12 STOP_TRANSMISSION */
+ SDIO_CmdInitStructure.SDIO_Argument = 0x0;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_STOP_TRANSMISSION;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_STOP_TRANSMISSION);
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_Erase
+* Description : Allows to erase memory area specified for the given card.
+* Input : - startaddr: the start address.
+* - endaddr: the end address.
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_Erase(u32 startaddr, u32 endaddr)
+{
+ SD_Error errorstatus = SD_OK;
+ u32 delay = 0;
+ vu32 maxdelay = 0;
+ u8 cardstate = 0;
+
+ /* Check if the card coomnd class supports erase command */
+ if (((CSD_Tab[1] >> 20) & SD_CCCC_ERASE) == 0)
+ {
+ errorstatus = SD_REQUEST_NOT_APPLICABLE;
+ return(errorstatus);
+ }
+
+ maxdelay = 72000 / ((SDIO->CLKCR & 0xFF) + 2);
+
+ if (SDIO_GetResponse(SDIO_RESP1) & SD_CARD_LOCKED)
+ {
+ errorstatus = SD_LOCK_UNLOCK_FAILED;
+ return(errorstatus);
+ }
+
+ /* According to sd-card spec 1.0 ERASE_GROUP_START (CMD32) and erase_group_end(CMD33) */
+ if ((SDIO_SECURE_DIGITAL_CARD == CardType) || (SDIO_HIGH_CAPACITY_SD_CARD == CardType))
+ {
+ /* Send CMD32 SD_ERASE_GRP_START with argument as addr */
+ SDIO_CmdInitStructure.SDIO_Argument = startaddr;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SD_ERASE_GRP_START;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_SD_ERASE_GRP_START);
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ /* Send CMD33 SD_ERASE_GRP_END with argument as addr */
+ SDIO_CmdInitStructure.SDIO_Argument = endaddr;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SD_ERASE_GRP_END;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_SD_ERASE_GRP_END);
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+ }
+
+ /* Send CMD38 ERASE */
+ SDIO_CmdInitStructure.SDIO_Argument = 0;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_ERASE;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_ERASE);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ for (delay = 0; delay < maxdelay; delay++)
+ {}
+
+ /* Wait till the card is in programming state */
+ errorstatus = IsCardProgramming(&cardstate);
+
+ while ((errorstatus == SD_OK) && ((SD_CARD_PROGRAMMING == cardstate) || (SD_CARD_RECEIVING == cardstate)))
+ {
+ errorstatus = IsCardProgramming(&cardstate);
+ }
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_SendStatus
+* Description : Returns the current card's status.
+* Input : pcardstatus: pointer to the buffer that will contain the SD
+* card status (Card Status register).
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_SendStatus(u32 *pcardstatus)
+{
+ SD_Error errorstatus = SD_OK;
+
+ if (pcardstatus == NULL)
+ {
+ errorstatus = SD_INVALID_PARAMETER;
+ return(errorstatus);
+ }
+
+ SDIO_CmdInitStructure.SDIO_Argument = (u32) RCA << 16;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SEND_STATUS;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+
+ errorstatus = CmdResp1Error(SDIO_SEND_STATUS);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ *pcardstatus = SDIO_GetResponse(SDIO_RESP1);
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_SendSDStatus
+* Description : Returns the current SD card's status.
+* Input : psdstatus: pointer to the buffer that will contain the SD
+* card status (SD Status register).
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_SendSDStatus(u32 *psdstatus)
+{
+ SD_Error errorstatus = SD_OK;
+ u32 count = 0;
+
+ if (SDIO_GetResponse(SDIO_RESP1) & SD_CARD_LOCKED)
+ {
+ errorstatus = SD_LOCK_UNLOCK_FAILED;
+ return(errorstatus);
+ }
+
+ /* Set block size for card if it is not equal to current block size for card. */
+ SDIO_CmdInitStructure.SDIO_Argument = 64;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SET_BLOCKLEN;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_SET_BLOCKLEN);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ /* CMD55 */
+ SDIO_CmdInitStructure.SDIO_Argument = (u32) RCA << 16;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_APP_CMD;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+ errorstatus = CmdResp1Error(SDIO_APP_CMD);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ SDIO_DataInitStructure.SDIO_DataTimeOut = SD_DATATIMEOUT;
+ SDIO_DataInitStructure.SDIO_DataLength = 64;
+ SDIO_DataInitStructure.SDIO_DataBlockSize = SDIO_DataBlockSize_64b;
+ SDIO_DataInitStructure.SDIO_TransferDir = SDIO_TransferDir_ToSDIO;
+ SDIO_DataInitStructure.SDIO_TransferMode = SDIO_TransferMode_Block;
+ SDIO_DataInitStructure.SDIO_DPSM = SDIO_DPSM_Enable;
+ SDIO_DataConfig(&SDIO_DataInitStructure);
+
+
+ /* Send ACMD13 SD_APP_STAUS with argument as card's RCA.*/
+ SDIO_CmdInitStructure.SDIO_Argument = 0;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SD_APP_STAUS;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+ errorstatus = CmdResp1Error(SDIO_SD_APP_STAUS);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ while (!(SDIO->STA &(SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DBCKEND | SDIO_FLAG_STBITERR)))
+ {
+ if (SDIO_GetFlagStatus(SDIO_FLAG_RXFIFOHF) != RESET)
+ {
+ for (count = 0; count < 8; count++)
+ {
+ *(psdstatus + count) = SDIO_ReadData();
+ }
+ psdstatus += 8;
+ }
+ }
+
+ if (SDIO_GetFlagStatus(SDIO_FLAG_DTIMEOUT) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_DTIMEOUT);
+ errorstatus = SD_DATA_TIMEOUT;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_DCRCFAIL) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_DCRCFAIL);
+ errorstatus = SD_DATA_CRC_FAIL;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_RXOVERR) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_RXOVERR);
+ errorstatus = SD_RX_OVERRUN;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_STBITERR) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_STBITERR);
+ errorstatus = SD_START_BIT_ERR;
+ return(errorstatus);
+ }
+
+ while (SDIO_GetFlagStatus(SDIO_FLAG_RXDAVL) != RESET)
+ {
+ *psdstatus = SDIO_ReadData();
+ psdstatus++;
+ }
+
+ /* Clear all the static status flags*/
+ SDIO_ClearFlag(SDIO_STATIC_FLAGS);
+ psdstatus -= 16;
+ for (count = 0; count < 16; count++)
+ {
+ psdstatus[count] = ((psdstatus[count] & SD_0TO7BITS) << 24) |((psdstatus[count] & SD_8TO15BITS) << 8) |
+ ((psdstatus[count] & SD_16TO23BITS) >> 8) |((psdstatus[count] & SD_24TO31BITS) >> 24);
+ }
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SD_ProcessIRQSrc
+* Description : Allows to process all the interrupts that are high.
+* Input : None
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+SD_Error SD_ProcessIRQSrc(void)
+{
+ u32 count = 0, restwords = 0;
+
+ if (DeviceMode == SD_INTERRUPT_MODE)
+ {
+ if (SDIO_GetITStatus(SDIO_IT_RXFIFOHF) != RESET)
+ {
+ for (count = 0; count < SD_HALFFIFO; count++)
+ {
+ *(DestBuffer + count) = SDIO_ReadData();
+ }
+ DestBuffer += SD_HALFFIFO;
+ NumberOfBytes += SD_HALFFIFOBYTES;
+ }
+ else if (SDIO_GetITStatus(SDIO_IT_TXFIFOHE) != RESET)
+ {
+ if ((TotalNumberOfBytes - NumberOfBytes) < SD_HALFFIFOBYTES)
+ {
+ restwords = ((TotalNumberOfBytes - NumberOfBytes) % 4 == 0) ?
+ ((TotalNumberOfBytes - NumberOfBytes) / 4) :
+ ((TotalNumberOfBytes - NumberOfBytes) / 4 + 1);
+
+ for (count = 0; count < restwords; count++, SrcBuffer++, NumberOfBytes += 4)
+ {
+ SDIO_WriteData(*SrcBuffer);
+ }
+ }
+ else
+ {
+ for (count = 0; count < SD_HALFFIFO; count++)
+ {
+ SDIO_WriteData(*(SrcBuffer + count));
+ }
+
+ SrcBuffer += SD_HALFFIFO;
+ NumberOfBytes += SD_HALFFIFOBYTES;
+ }
+ }
+ }
+
+ if (SDIO_GetITStatus(SDIO_IT_DATAEND) != RESET)
+ {
+ if (DeviceMode != SD_DMA_MODE)
+ {
+ while ((SDIO_GetFlagStatus(SDIO_FLAG_RXDAVL) != RESET) && (NumberOfBytes < TotalNumberOfBytes))
+ {
+ *DestBuffer = SDIO_ReadData();
+ DestBuffer++;
+ NumberOfBytes += 4;
+ }
+ }
+
+ if (StopCondition == 1)
+ {
+ TransferError = SD_StopTransfer();
+ }
+ else
+ {
+ TransferError = SD_OK;
+ }
+ SDIO_ClearITPendingBit(SDIO_IT_DATAEND);
+ SDIO_ITConfig(SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_DATAEND |
+ SDIO_IT_TXFIFOHE | SDIO_IT_RXFIFOHF | SDIO_IT_TXUNDERR |
+ SDIO_IT_RXOVERR | SDIO_IT_STBITERR, DISABLE);
+ TransferEnd = 1;
+ NumberOfBytes = 0;
+ return(TransferError);
+ }
+
+ if (SDIO_GetITStatus(SDIO_IT_DCRCFAIL) != RESET)
+ {
+ SDIO_ClearITPendingBit(SDIO_IT_DCRCFAIL);
+ SDIO_ITConfig(SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_DATAEND |
+ SDIO_IT_TXFIFOHE | SDIO_IT_RXFIFOHF | SDIO_IT_TXUNDERR |
+ SDIO_IT_RXOVERR | SDIO_IT_STBITERR, DISABLE);
+ NumberOfBytes = 0;
+ TransferError = SD_DATA_CRC_FAIL;
+ return(SD_DATA_CRC_FAIL);
+ }
+
+ if (SDIO_GetITStatus(SDIO_IT_DTIMEOUT) != RESET)
+ {
+ SDIO_ClearITPendingBit(SDIO_IT_DTIMEOUT);
+ SDIO_ITConfig(SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_DATAEND |
+ SDIO_IT_TXFIFOHE | SDIO_IT_RXFIFOHF | SDIO_IT_TXUNDERR |
+ SDIO_IT_RXOVERR | SDIO_IT_STBITERR, DISABLE);
+ NumberOfBytes = 0;
+ TransferError = SD_DATA_TIMEOUT;
+ return(SD_DATA_TIMEOUT);
+ }
+
+ if (SDIO_GetITStatus(SDIO_IT_RXOVERR) != RESET)
+ {
+ SDIO_ClearITPendingBit(SDIO_IT_RXOVERR);
+ SDIO_ITConfig(SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_DATAEND |
+ SDIO_IT_TXFIFOHE | SDIO_IT_RXFIFOHF | SDIO_IT_TXUNDERR |
+ SDIO_IT_RXOVERR | SDIO_IT_STBITERR, DISABLE);
+ NumberOfBytes = 0;
+ TransferError = SD_RX_OVERRUN;
+ return(SD_RX_OVERRUN);
+ }
+
+ if (SDIO_GetITStatus(SDIO_IT_TXUNDERR) != RESET)
+ {
+ SDIO_ClearITPendingBit(SDIO_IT_TXUNDERR);
+ SDIO_ITConfig(SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_DATAEND |
+ SDIO_IT_TXFIFOHE | SDIO_IT_RXFIFOHF | SDIO_IT_TXUNDERR |
+ SDIO_IT_RXOVERR | SDIO_IT_STBITERR, DISABLE);
+ NumberOfBytes = 0;
+ TransferError = SD_TX_UNDERRUN;
+ return(SD_TX_UNDERRUN);
+ }
+
+ if (SDIO_GetITStatus(SDIO_IT_STBITERR) != RESET)
+ {
+ SDIO_ClearITPendingBit(SDIO_IT_STBITERR);
+ SDIO_ITConfig(SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_DATAEND |
+ SDIO_IT_TXFIFOHE | SDIO_IT_RXFIFOHF | SDIO_IT_TXUNDERR |
+ SDIO_IT_RXOVERR | SDIO_IT_STBITERR, DISABLE);
+ NumberOfBytes = 0;
+ TransferError = SD_START_BIT_ERR;
+ return(SD_START_BIT_ERR);
+ }
+
+ return(SD_OK);
+}
+
+/*******************************************************************************
+* Function Name : CmdError
+* Description : Checks for error conditions for CMD0.
+* Input : None
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+static SD_Error CmdError(void)
+{
+ SD_Error errorstatus = SD_OK;
+ u32 timeout;
+
+ timeout = SDIO_CMD0TIMEOUT; /* 10000 */
+
+ while ((timeout > 0) && (SDIO_GetFlagStatus(SDIO_FLAG_CMDSENT) == RESET))
+ {
+ timeout--;
+ }
+
+ if (timeout == 0)
+ {
+ errorstatus = SD_CMD_RSP_TIMEOUT;
+ return(errorstatus);
+ }
+
+ /* Clear all the static flags */
+ SDIO_ClearFlag(SDIO_STATIC_FLAGS);
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : CmdResp7Error
+* Description : Checks for error conditions for R7.
+* response.
+* Input : None
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+static SD_Error CmdResp7Error(void)
+{
+ SD_Error errorstatus = SD_OK;
+ u32 status;
+ u32 timeout = SDIO_CMD0TIMEOUT;
+
+ status = SDIO->STA;
+
+ while (!(status & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CMDREND | SDIO_FLAG_CTIMEOUT)) && (timeout > 0))
+ {
+ timeout--;
+ status = SDIO->STA;
+ }
+
+ if ((timeout == 0) || (status & SDIO_FLAG_CTIMEOUT))
+ {
+ /* Card is not V2.0 complient or card does not support the set voltage range */
+ errorstatus = SD_CMD_RSP_TIMEOUT;
+ SDIO_ClearFlag(SDIO_FLAG_CTIMEOUT);
+ return(errorstatus);
+ }
+
+ if (status & SDIO_FLAG_CMDREND)
+ {
+ /* Card is SD V2.0 compliant */
+ errorstatus = SD_OK;
+ return(errorstatus);
+ }
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : CmdResp1Error
+* Description : Checks for error conditions for R1.
+* response
+* Input : cmd: The sent command index.
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+static SD_Error CmdResp1Error(u8 cmd)
+{
+ SD_Error errorstatus = SD_OK;
+ u32 status;
+ u32 response_r1;
+
+ status = SDIO->STA;
+
+ while (!(status & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CMDREND | SDIO_FLAG_CTIMEOUT)))
+ {
+ status = SDIO->STA;
+ }
+
+ if (status & SDIO_FLAG_CTIMEOUT)
+ {
+ errorstatus = SD_CMD_RSP_TIMEOUT;
+ SDIO_ClearFlag(SDIO_FLAG_CTIMEOUT);
+ return(errorstatus);
+ }
+ else if (status & SDIO_FLAG_CCRCFAIL)
+ {
+ errorstatus = SD_CMD_CRC_FAIL;
+ SDIO_ClearFlag(SDIO_FLAG_CCRCFAIL);
+ return(errorstatus);
+ }
+
+ /* Check response received is of desired command */
+ if (SDIO_GetCommandResponse() != cmd)
+ {
+ errorstatus = SD_ILLEGAL_CMD;
+ return(errorstatus);
+ }
+
+ /* Clear all the static flags */
+ SDIO_ClearFlag(SDIO_STATIC_FLAGS);
+
+ /* We have received response, retrieve it for analysis */
+ response_r1 = SDIO_GetResponse(SDIO_RESP1);
+
+ if ((response_r1 & SD_OCR_ERRORBITS) == SD_ALLZERO)
+ {
+ return(errorstatus);
+ }
+
+ if (response_r1 & SD_OCR_ADDR_OUT_OF_RANGE)
+ {
+ return(SD_ADDR_OUT_OF_RANGE);
+ }
+
+ if (response_r1 & SD_OCR_ADDR_MISALIGNED)
+ {
+ return(SD_ADDR_MISALIGNED);
+ }
+
+ if (response_r1 & SD_OCR_BLOCK_LEN_ERR)
+ {
+ return(SD_BLOCK_LEN_ERR);
+ }
+
+ if (response_r1 & SD_OCR_ERASE_SEQ_ERR)
+ {
+ return(SD_ERASE_SEQ_ERR);
+ }
+
+ if (response_r1 & SD_OCR_BAD_ERASE_PARAM)
+ {
+ return(SD_BAD_ERASE_PARAM);
+ }
+
+ if (response_r1 & SD_OCR_WRITE_PROT_VIOLATION)
+ {
+ return(SD_WRITE_PROT_VIOLATION);
+ }
+
+ if (response_r1 & SD_OCR_LOCK_UNLOCK_FAILED)
+ {
+ return(SD_LOCK_UNLOCK_FAILED);
+ }
+
+ if (response_r1 & SD_OCR_COM_CRC_FAILED)
+ {
+ return(SD_COM_CRC_FAILED);
+ }
+
+ if (response_r1 & SD_OCR_ILLEGAL_CMD)
+ {
+ return(SD_ILLEGAL_CMD);
+ }
+
+ if (response_r1 & SD_OCR_CARD_ECC_FAILED)
+ {
+ return(SD_CARD_ECC_FAILED);
+ }
+
+ if (response_r1 & SD_OCR_CC_ERROR)
+ {
+ return(SD_CC_ERROR);
+ }
+
+ if (response_r1 & SD_OCR_GENERAL_UNKNOWN_ERROR)
+ {
+ return(SD_GENERAL_UNKNOWN_ERROR);
+ }
+
+ if (response_r1 & SD_OCR_STREAM_READ_UNDERRUN)
+ {
+ return(SD_STREAM_READ_UNDERRUN);
+ }
+
+ if (response_r1 & SD_OCR_STREAM_WRITE_OVERRUN)
+ {
+ return(SD_STREAM_WRITE_OVERRUN);
+ }
+
+ if (response_r1 & SD_OCR_CID_CSD_OVERWRIETE)
+ {
+ return(SD_CID_CSD_OVERWRITE);
+ }
+
+ if (response_r1 & SD_OCR_WP_ERASE_SKIP)
+ {
+ return(SD_WP_ERASE_SKIP);
+ }
+
+ if (response_r1 & SD_OCR_CARD_ECC_DISABLED)
+ {
+ return(SD_CARD_ECC_DISABLED);
+ }
+
+ if (response_r1 & SD_OCR_ERASE_RESET)
+ {
+ return(SD_ERASE_RESET);
+ }
+
+ if (response_r1 & SD_OCR_AKE_SEQ_ERROR)
+ {
+ return(SD_AKE_SEQ_ERROR);
+ }
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : CmdResp3Error
+* Description : Checks for error conditions for R3 (OCR).
+* response.
+* Input : None
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+static SD_Error CmdResp3Error(void)
+{
+ SD_Error errorstatus = SD_OK;
+ u32 status;
+
+ status = SDIO->STA;
+
+ while (!(status & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CMDREND | SDIO_FLAG_CTIMEOUT)))
+ {
+ status = SDIO->STA;
+ }
+
+ if (status & SDIO_FLAG_CTIMEOUT)
+ {
+ errorstatus = SD_CMD_RSP_TIMEOUT;
+ SDIO_ClearFlag(SDIO_FLAG_CTIMEOUT);
+ return(errorstatus);
+ }
+ /* Clear all the static flags */
+ SDIO_ClearFlag(SDIO_STATIC_FLAGS);
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : CmdResp2Error
+* Description : Checks for error conditions for R2 (CID or CSD).
+* response.
+* Input : None
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+static SD_Error CmdResp2Error(void)
+{
+ SD_Error errorstatus = SD_OK;
+ u32 status;
+
+ status = SDIO->STA;
+
+ while (!(status & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CTIMEOUT | SDIO_FLAG_CMDREND)))
+ {
+ status = SDIO->STA;
+ }
+
+ if (status & SDIO_FLAG_CTIMEOUT)
+ {
+ errorstatus = SD_CMD_RSP_TIMEOUT;
+ SDIO_ClearFlag(SDIO_FLAG_CTIMEOUT);
+ return(errorstatus);
+ }
+ else if (status & SDIO_FLAG_CCRCFAIL)
+ {
+ errorstatus = SD_CMD_CRC_FAIL;
+ SDIO_ClearFlag(SDIO_FLAG_CCRCFAIL);
+ return(errorstatus);
+ }
+
+ /* Clear all the static flags */
+ SDIO_ClearFlag(SDIO_STATIC_FLAGS);
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : CmdResp6Error
+* Description : Checks for error conditions for R6 (RCA).
+* response.
+* Input : - cmd: The sent command index.
+* - prca: pointer to the variable that will contain the SD
+* card relative address RCA.
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+static SD_Error CmdResp6Error(u8 cmd, u16 *prca)
+{
+ SD_Error errorstatus = SD_OK;
+ u32 status;
+ u32 response_r1;
+
+ status = SDIO->STA;
+
+ while (!(status & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CTIMEOUT | SDIO_FLAG_CMDREND)))
+ {
+ status = SDIO->STA;
+ }
+
+ if (status & SDIO_FLAG_CTIMEOUT)
+ {
+ errorstatus = SD_CMD_RSP_TIMEOUT;
+ SDIO_ClearFlag(SDIO_FLAG_CTIMEOUT);
+ return(errorstatus);
+ }
+ else if (status & SDIO_FLAG_CCRCFAIL)
+ {
+ errorstatus = SD_CMD_CRC_FAIL;
+ SDIO_ClearFlag(SDIO_FLAG_CCRCFAIL);
+ return(errorstatus);
+ }
+
+ /* Check response received is of desired command */
+ if (SDIO_GetCommandResponse() != cmd)
+ {
+ errorstatus = SD_ILLEGAL_CMD;
+ return(errorstatus);
+ }
+
+ /* Clear all the static flags */
+ SDIO_ClearFlag(SDIO_STATIC_FLAGS);
+
+ /* We have received response, retrieve it. */
+ response_r1 = SDIO_GetResponse(SDIO_RESP1);
+
+ if (SD_ALLZERO == (response_r1 & (SD_R6_GENERAL_UNKNOWN_ERROR | SD_R6_ILLEGAL_CMD | SD_R6_COM_CRC_FAILED)))
+ {
+ *prca = (u16) (response_r1 >> 16);
+ return(errorstatus);
+ }
+
+ if (response_r1 & SD_R6_GENERAL_UNKNOWN_ERROR)
+ {
+ return(SD_GENERAL_UNKNOWN_ERROR);
+ }
+
+ if (response_r1 & SD_R6_ILLEGAL_CMD)
+ {
+ return(SD_ILLEGAL_CMD);
+ }
+
+ if (response_r1 & SD_R6_COM_CRC_FAILED)
+ {
+ return(SD_COM_CRC_FAILED);
+ }
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : SDEnWideBus
+* Description : Enables or disables the SDIO wide bus mode.
+* Input : NewState: new state of the SDIO wide bus mode.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+static SD_Error SDEnWideBus(FunctionalState NewState)
+{
+ SD_Error errorstatus = SD_OK;
+
+ u32 scr[2] = {0, 0};
+
+ if (SDIO_GetResponse(SDIO_RESP1) & SD_CARD_LOCKED)
+ {
+ errorstatus = SD_LOCK_UNLOCK_FAILED;
+ return(errorstatus);
+ }
+
+ /* Get SCR Register */
+ errorstatus = FindSCR(RCA, scr);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ /* If wide bus operation to be enabled */
+ if (NewState == ENABLE)
+ {
+ /* If requested card supports wide bus operation */
+ if ((scr[1] & SD_WIDE_BUS_SUPPORT) != SD_ALLZERO)
+ {
+ /* Send CMD55 APP_CMD with argument as card's RCA.*/
+ SDIO_CmdInitStructure.SDIO_Argument = (u32) RCA << 16;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_APP_CMD;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_APP_CMD);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ /* Send ACMD6 APP_CMD with argument as 2 for wide bus mode */
+ SDIO_CmdInitStructure.SDIO_Argument = 0x2;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_APP_SD_SET_BUSWIDTH;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_APP_SD_SET_BUSWIDTH);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+ return(errorstatus);
+ }
+ else
+ {
+ errorstatus = SD_REQUEST_NOT_APPLICABLE;
+ return(errorstatus);
+ }
+ } /* If wide bus operation to be disabled */
+ else
+ {
+ /* If requested card supports 1 bit mode operation */
+ if ((scr[1] & SD_SINGLE_BUS_SUPPORT) != SD_ALLZERO)
+ {
+ /* Send CMD55 APP_CMD with argument as card's RCA.*/
+ SDIO_CmdInitStructure.SDIO_Argument = (u32) RCA << 16;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_APP_CMD;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+
+ errorstatus = CmdResp1Error(SDIO_APP_CMD);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ /* Send ACMD6 APP_CMD with argument as 2 for wide bus mode */
+ SDIO_CmdInitStructure.SDIO_Argument = 0x00;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_APP_SD_SET_BUSWIDTH;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_APP_SD_SET_BUSWIDTH);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ return(errorstatus);
+ }
+ else
+ {
+ errorstatus = SD_REQUEST_NOT_APPLICABLE;
+ return(errorstatus);
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : IsCardProgramming
+* Description : Checks if the SD card is in programming state.
+* Input : pstatus: pointer to the variable that will contain the SD
+* card state.
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+static SD_Error IsCardProgramming(u8 *pstatus)
+{
+ SD_Error errorstatus = SD_OK;
+ vu32 respR1 = 0, status = 0;
+
+ SDIO_CmdInitStructure.SDIO_Argument = (u32) RCA << 16;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SEND_STATUS;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ status = SDIO->STA;
+ while (!(status & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CMDREND | SDIO_FLAG_CTIMEOUT)))
+ {
+ status = SDIO->STA;
+ }
+
+ if (status & SDIO_FLAG_CTIMEOUT)
+ {
+ errorstatus = SD_CMD_RSP_TIMEOUT;
+ SDIO_ClearFlag(SDIO_FLAG_CTIMEOUT);
+ return(errorstatus);
+ }
+ else if (status & SDIO_FLAG_CCRCFAIL)
+ {
+ errorstatus = SD_CMD_CRC_FAIL;
+ SDIO_ClearFlag(SDIO_FLAG_CCRCFAIL);
+ return(errorstatus);
+ }
+
+ status = (u32)SDIO_GetCommandResponse();
+
+ /* Check response received is of desired command */
+ if (status != SDIO_SEND_STATUS)
+ {
+ errorstatus = SD_ILLEGAL_CMD;
+ return(errorstatus);
+ }
+
+ /* Clear all the static flags */
+ SDIO_ClearFlag(SDIO_STATIC_FLAGS);
+
+
+ /* We have received response, retrieve it for analysis */
+ respR1 = SDIO_GetResponse(SDIO_RESP1);
+
+ /* Find out card status */
+ *pstatus = (u8) ((respR1 >> 9) & 0x0000000F);
+
+ if ((respR1 & SD_OCR_ERRORBITS) == SD_ALLZERO)
+ {
+ return(errorstatus);
+ }
+
+ if (respR1 & SD_OCR_ADDR_OUT_OF_RANGE)
+ {
+ return(SD_ADDR_OUT_OF_RANGE);
+ }
+
+ if (respR1 & SD_OCR_ADDR_MISALIGNED)
+ {
+ return(SD_ADDR_MISALIGNED);
+ }
+
+ if (respR1 & SD_OCR_BLOCK_LEN_ERR)
+ {
+ return(SD_BLOCK_LEN_ERR);
+ }
+
+ if (respR1 & SD_OCR_ERASE_SEQ_ERR)
+ {
+ return(SD_ERASE_SEQ_ERR);
+ }
+
+ if (respR1 & SD_OCR_BAD_ERASE_PARAM)
+ {
+ return(SD_BAD_ERASE_PARAM);
+ }
+
+ if (respR1 & SD_OCR_WRITE_PROT_VIOLATION)
+ {
+ return(SD_WRITE_PROT_VIOLATION);
+ }
+
+ if (respR1 & SD_OCR_LOCK_UNLOCK_FAILED)
+ {
+ return(SD_LOCK_UNLOCK_FAILED);
+ }
+
+ if (respR1 & SD_OCR_COM_CRC_FAILED)
+ {
+ return(SD_COM_CRC_FAILED);
+ }
+
+ if (respR1 & SD_OCR_ILLEGAL_CMD)
+ {
+ return(SD_ILLEGAL_CMD);
+ }
+
+ if (respR1 & SD_OCR_CARD_ECC_FAILED)
+ {
+ return(SD_CARD_ECC_FAILED);
+ }
+
+ if (respR1 & SD_OCR_CC_ERROR)
+ {
+ return(SD_CC_ERROR);
+ }
+
+ if (respR1 & SD_OCR_GENERAL_UNKNOWN_ERROR)
+ {
+ return(SD_GENERAL_UNKNOWN_ERROR);
+ }
+
+ if (respR1 & SD_OCR_STREAM_READ_UNDERRUN)
+ {
+ return(SD_STREAM_READ_UNDERRUN);
+ }
+
+ if (respR1 & SD_OCR_STREAM_WRITE_OVERRUN)
+ {
+ return(SD_STREAM_WRITE_OVERRUN);
+ }
+
+ if (respR1 & SD_OCR_CID_CSD_OVERWRIETE)
+ {
+ return(SD_CID_CSD_OVERWRITE);
+ }
+
+ if (respR1 & SD_OCR_WP_ERASE_SKIP)
+ {
+ return(SD_WP_ERASE_SKIP);
+ }
+
+ if (respR1 & SD_OCR_CARD_ECC_DISABLED)
+ {
+ return(SD_CARD_ECC_DISABLED);
+ }
+
+ if (respR1 & SD_OCR_ERASE_RESET)
+ {
+ return(SD_ERASE_RESET);
+ }
+
+ if (respR1 & SD_OCR_AKE_SEQ_ERROR)
+ {
+ return(SD_AKE_SEQ_ERROR);
+ }
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : FindSCR
+* Description : Find the SD card SCR register value.
+* Input : - rca: selected card address.
+* - pscr: pointer to the buffer that will contain the SCR value.
+* Output : None
+* Return : SD_Error: SD Card Error code.
+*******************************************************************************/
+static SD_Error FindSCR(u16 rca, u32 *pscr)
+{
+ u32 index = 0;
+ SD_Error errorstatus = SD_OK;
+ u32 tempscr[2] = {0, 0};
+
+ /* Set Block Size To 8 Bytes */
+ /* Send CMD55 APP_CMD with argument as card's RCA */
+ SDIO_CmdInitStructure.SDIO_Argument = (u32)8;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SET_BLOCKLEN;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_SET_BLOCKLEN);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ /* Send CMD55 APP_CMD with argument as card's RCA */
+ SDIO_CmdInitStructure.SDIO_Argument = (u32) RCA << 16;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_APP_CMD;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_APP_CMD);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+ SDIO_DataInitStructure.SDIO_DataTimeOut = SD_DATATIMEOUT;
+ SDIO_DataInitStructure.SDIO_DataLength = 8;
+ SDIO_DataInitStructure.SDIO_DataBlockSize = SDIO_DataBlockSize_8b;
+ SDIO_DataInitStructure.SDIO_TransferDir = SDIO_TransferDir_ToSDIO;
+ SDIO_DataInitStructure.SDIO_TransferMode = SDIO_TransferMode_Block;
+ SDIO_DataInitStructure.SDIO_DPSM = SDIO_DPSM_Enable;
+ SDIO_DataConfig(&SDIO_DataInitStructure);
+
+
+ /* Send ACMD51 SD_APP_SEND_SCR with argument as 0 */
+ SDIO_CmdInitStructure.SDIO_Argument = 0x0;
+ SDIO_CmdInitStructure.SDIO_CmdIndex = SDIO_SD_APP_SEND_SCR;
+ SDIO_CmdInitStructure.SDIO_Response = SDIO_Response_Short;
+ SDIO_CmdInitStructure.SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStructure.SDIO_CPSM = SDIO_CPSM_Enable;
+ SDIO_SendCommand(&SDIO_CmdInitStructure);
+
+ errorstatus = CmdResp1Error(SDIO_SD_APP_SEND_SCR);
+
+ if (errorstatus != SD_OK)
+ {
+ return(errorstatus);
+ }
+
+ while (!(SDIO->STA & (SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DBCKEND | SDIO_FLAG_STBITERR)))
+ {
+ if (SDIO_GetFlagStatus(SDIO_FLAG_RXDAVL) != RESET)
+ {
+ *(tempscr + index) = SDIO_ReadData();
+ index++;
+ }
+ }
+
+ if (SDIO_GetFlagStatus(SDIO_FLAG_DTIMEOUT) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_DTIMEOUT);
+ errorstatus = SD_DATA_TIMEOUT;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_DCRCFAIL) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_DCRCFAIL);
+ errorstatus = SD_DATA_CRC_FAIL;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_RXOVERR) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_RXOVERR);
+ errorstatus = SD_RX_OVERRUN;
+ return(errorstatus);
+ }
+ else if (SDIO_GetFlagStatus(SDIO_FLAG_STBITERR) != RESET)
+ {
+ SDIO_ClearFlag(SDIO_FLAG_STBITERR);
+ errorstatus = SD_START_BIT_ERR;
+ return(errorstatus);
+ }
+
+ /* Clear all the static flags */
+ SDIO_ClearFlag(SDIO_STATIC_FLAGS);
+
+ *(pscr + 1) = ((tempscr[0] & SD_0TO7BITS) << 24) | ((tempscr[0] & SD_8TO15BITS) << 8) | ((tempscr[0] & SD_16TO23BITS) >> 8) | ((tempscr[0] & SD_24TO31BITS) >> 24);
+
+ *(pscr) = ((tempscr[1] & SD_0TO7BITS) << 24) | ((tempscr[1] & SD_8TO15BITS) << 8) | ((tempscr[1] & SD_16TO23BITS) >> 8) | ((tempscr[1] & SD_24TO31BITS) >> 24);
+
+ return(errorstatus);
+}
+
+/*******************************************************************************
+* Function Name : convert_from_bytes_to_power_of_two
+* Description : Converts the number of bytes in power of two and returns the
+* power.
+* Input : NumberOfBytes: number of bytes.
+* Output : None
+* Return : None
+*******************************************************************************/
+static u8 convert_from_bytes_to_power_of_two(u16 NumberOfBytes)
+{
+ u8 count = 0;
+
+ while (NumberOfBytes != 1)
+ {
+ NumberOfBytes >>= 1;
+ count++;
+ }
+ return(count);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the SDIO Corresponding GPIO Ports
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+static void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* GPIOC and GPIOD Periph clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC | RCC_APB2Periph_GPIOD, ENABLE);
+
+ /* Configure PC.08, PC.09, PC.10, PC.11, PC.12 pin: D0, D1, D2, D3, CLK pin */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10 | GPIO_Pin_11 | GPIO_Pin_12;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+
+ /* Configure PD.02 CMD line */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2;
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : DMA_TxConfiguration
+* Description : Configures the DMA2 Channel4 for SDIO Tx request.
+* Input : - BufferSRC: pointer to the source buffer
+* - BufferSize: buffer size
+* Output : None
+* Return : None
+*******************************************************************************/
+static void DMA_TxConfiguration(u32 *BufferSRC, u32 BufferSize)
+{
+ DMA_InitTypeDef DMA_InitStructure;
+
+ DMA_ClearFlag(DMA2_FLAG_TC4 | DMA2_FLAG_TE4 | DMA2_FLAG_HT4 | DMA2_FLAG_GL4);
+
+ /* DMA2 Channel4 disable */
+ DMA_Cmd(DMA2_Channel4, DISABLE);
+
+ /* DMA2 Channel4 Config */
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)SDIO_FIFO_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)BufferSRC;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
+ DMA_InitStructure.DMA_BufferSize = BufferSize / 4;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA2_Channel4, &DMA_InitStructure);
+
+ /* DMA2 Channel4 enable */
+ DMA_Cmd(DMA2_Channel4, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : DMA_RxConfiguration
+* Description : Configures the DMA2 Channel4 for SDIO Rx request.
+* Input : - BufferDST: pointer to the destination buffer
+* - BufferSize: buffer size
+* Output : None
+* Return : None
+*******************************************************************************/
+static void DMA_RxConfiguration(u32 *BufferDST, u32 BufferSize)
+{
+ DMA_InitTypeDef DMA_InitStructure;
+
+ DMA_ClearFlag(DMA2_FLAG_TC4 | DMA2_FLAG_TE4 | DMA2_FLAG_HT4 | DMA2_FLAG_GL4);
+
+ /* DMA2 Channel4 disable */
+ DMA_Cmd(DMA2_Channel4, DISABLE);
+
+ /* DMA2 Channel4 Config */
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)SDIO_FIFO_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)BufferDST;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = BufferSize / 4;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA2_Channel4, &DMA_InitStructure);
+
+ /* DMA2 Channel4 enable */
+ DMA_Cmd(DMA2_Channel4, ENABLE);
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SDIO/sdcard.h b/src/stm32lib/examples/SDIO/sdcard.h new file mode 100755 index 0000000..8289dda --- /dev/null +++ b/src/stm32lib/examples/SDIO/sdcard.h @@ -0,0 +1,252 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : sdcard.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains all the functions prototypes for the
+* SD Card driver firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __SDCARD_H
+#define __SDCARD_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+typedef enum
+{
+ /* SDIO specific error defines */
+ SD_CMD_CRC_FAIL = (1), /* Command response received (but CRC check failed) */
+ SD_DATA_CRC_FAIL = (2), /* Data bock sent/received (CRC check Failed) */
+ SD_CMD_RSP_TIMEOUT = (3), /* Command response timeout */
+ SD_DATA_TIMEOUT = (4), /* Data time out */
+ SD_TX_UNDERRUN = (5), /* Transmit FIFO under-run */
+ SD_RX_OVERRUN = (6), /* Receive FIFO over-run */
+ SD_START_BIT_ERR = (7), /* Start bit not detected on all data signals in widE bus mode */
+ SD_CMD_OUT_OF_RANGE = (8), /* CMD's argument was out of range.*/
+ SD_ADDR_MISALIGNED = (9), /* Misaligned address */
+ SD_BLOCK_LEN_ERR = (10), /* Transferred block length is not allowed for the card or the number of transferred bytes does not match the block length */
+ SD_ERASE_SEQ_ERR = (11), /* An error in the sequence of erase command occurs.*/
+ SD_BAD_ERASE_PARAM = (12), /* An Invalid selection for erase groups */
+ SD_WRITE_PROT_VIOLATION = (13), /* Attempt to program a write protect block */
+ SD_LOCK_UNLOCK_FAILED = (14), /* Sequence or password error has been detected in unlock command or if there was an attempt to access a locked card */
+ SD_COM_CRC_FAILED = (15), /* CRC check of the previous command failed */
+ SD_ILLEGAL_CMD = (16), /* Command is not legal for the card state */
+ SD_CARD_ECC_FAILED = (17), /* Card internal ECC was applied but failed to correct the data */
+ SD_CC_ERROR = (18), /* Internal card controller error */
+ SD_GENERAL_UNKNOWN_ERROR = (19), /* General or Unknown error */
+ SD_STREAM_READ_UNDERRUN = (20), /* The card could not sustain data transfer in stream read operation. */
+ SD_STREAM_WRITE_OVERRUN = (21), /* The card could not sustain data programming in stream mode */
+ SD_CID_CSD_OVERWRITE = (22), /* CID/CSD overwrite error */
+ SD_WP_ERASE_SKIP = (23), /* only partial address space was erased */
+ SD_CARD_ECC_DISABLED = (24), /* Command has been executed without using internal ECC */
+ SD_ERASE_RESET = (25), /* Erase sequence was cleared before executing because an out of erase sequence command was received */
+ SD_AKE_SEQ_ERROR = (26), /* Error in sequence of authentication. */
+ SD_INVALID_VOLTRANGE = (27),
+ SD_ADDR_OUT_OF_RANGE = (28),
+ SD_SWITCH_ERROR = (29),
+ SD_SDIO_DISABLED = (30),
+ SD_SDIO_FUNCTION_BUSY = (31),
+ SD_SDIO_FUNCTION_FAILED = (32),
+ SD_SDIO_UNKNOWN_FUNCTION = (33),
+
+ /* Standard error defines */
+ SD_INTERNAL_ERROR,
+ SD_NOT_CONFIGURED,
+ SD_REQUEST_PENDING,
+ SD_REQUEST_NOT_APPLICABLE,
+ SD_INVALID_PARAMETER,
+ SD_UNSUPPORTED_FEATURE,
+ SD_UNSUPPORTED_HW,
+ SD_ERROR,
+ SD_OK,
+} SD_Error;
+
+/* SDIO Commands Index */
+#define SDIO_GO_IDLE_STATE ((u8)0)
+#define SDIO_SEND_OP_COND ((u8)1)
+#define SDIO_ALL_SEND_CID ((u8)2)
+#define SDIO_SET_REL_ADDR ((u8)3) /* SDIO_SEND_REL_ADDR for SD Card */
+#define SDIO_SET_DSR ((u8)4)
+#define SDIO_SDIO_SEN_OP_COND ((u8)5)
+#define SDIO_HS_SWITCH ((u8)6)
+#define SDIO_SEL_DESEL_CARD ((u8)7)
+#define SDIO_HS_SEND_EXT_CSD ((u8)8)
+#define SDIO_SEND_CSD ((u8)9)
+#define SDIO_SEND_CID ((u8)10)
+#define SDIO_READ_DAT_UNTIL_STOP ((u8)11) /* SD Card doesn't support it */
+#define SDIO_STOP_TRANSMISSION ((u8)12)
+#define SDIO_SEND_STATUS ((u8)13)
+#define SDIO_HS_BUSTEST_READ ((u8)14)
+#define SDIO_GO_INACTIVE_STATE ((u8)15)
+#define SDIO_SET_BLOCKLEN ((u8)16)
+#define SDIO_READ_SINGLE_BLOCK ((u8)17)
+#define SDIO_READ_MULT_BLOCK ((u8)18)
+#define SDIO_HS_BUSTEST_WRITE ((u8)19)
+#define SDIO_WRITE_DAT_UNTIL_STOP ((u8)20) /* SD Card doesn't support it */
+#define SDIO_SET_BLOCK_COUNT ((u8)23) /* SD Card doesn't support it */
+#define SDIO_WRITE_SINGLE_BLOCK ((u8)24)
+#define SDIO_WRITE_MULT_BLOCK ((u8)25)
+#define SDIO_PROG_CID ((u8)26) /* reserved for manufacturers */
+#define SDIO_PROG_CSD ((u8)27)
+#define SDIO_SET_WRITE_PROT ((u8)28)
+#define SDIO_CLR_WRITE_PROT ((u8)29)
+#define SDIO_SEND_WRITE_PROT ((u8)30)
+#define SDIO_SD_ERASE_GRP_START ((u8)32) /* To set the address of the first write
+ block to be erased. (For SD card only) */
+#define SDIO_SD_ERASE_GRP_END ((u8)33) /* To set the address of the last write block of the
+ continuous range to be erased. (For SD card only) */
+#define SDIO_ERASE_GRP_START ((u8)35) /* To set the address of the first write block to be erased.
+ (For MMC card only spec 3.31) */
+
+#define SDIO_ERASE_GRP_END ((u8)36) /* To set the address of the last write block of the
+ continuous range to be erased. (For MMC card only spec 3.31) */
+
+#define SDIO_ERASE ((u8)38)
+#define SDIO_FAST_IO ((u8)39) /* SD Card doesn't support it */
+#define SDIO_GO_IRQ_STATE ((u8)40) /* SD Card doesn't support it */
+#define SDIO_LOCK_UNLOCK ((u8)42)
+#define SDIO_APP_CMD ((u8)55)
+#define SDIO_GEN_CMD ((u8)56)
+#define SDIO_NO_CMD ((u8)64)
+
+/* Following commands are SD Card Specific commands.
+ SDIO_APP_CMD should be sent before sending these
+ commands. */
+#define SDIO_APP_SD_SET_BUSWIDTH ((u8)6) /* For SD Card only */
+#define SDIO_SD_APP_STAUS ((u8)13) /* For SD Card only */
+#define SDIO_SD_APP_SEND_NUM_WRITE_BLOCKS ((u8)22) /* For SD Card only */
+#define SDIO_SD_APP_OP_COND ((u8)41) /* For SD Card only */
+#define SDIO_SD_APP_SET_CLR_CARD_DETECT ((u8)42) /* For SD Card only */
+#define SDIO_SD_APP_SEND_SCR ((u8)51) /* For SD Card only */
+#define SDIO_SDIO_RW_DIRECT ((u8)52) /* For SD I/O Card only */
+#define SDIO_SDIO_RW_EXTENDED ((u8)53) /* For SD I/O Card only */
+
+/* Following commands are SD Card Specific security commands.
+ SDIO_APP_CMD should be sent before sending these commands. */
+#define SDIO_SD_APP_GET_MKB ((u8)43) /* For SD Card only */
+#define SDIO_SD_APP_GET_MID ((u8)44) /* For SD Card only */
+#define SDIO_SD_APP_SET_CER_RN1 ((u8)45) /* For SD Card only */
+#define SDIO_SD_APP_GET_CER_RN2 ((u8)46) /* For SD Card only */
+#define SDIO_SD_APP_SET_CER_RES2 ((u8)47) /* For SD Card only */
+#define SDIO_SD_APP_GET_CER_RES1 ((u8)48) /* For SD Card only */
+#define SDIO_SD_APP_SECURE_READ_MULTIPLE_BLOCK ((u8)18) /* For SD Card only */
+#define SDIO_SD_APP_SECURE_WRITE_MULTIPLE_BLOCK ((u8)25) /* For SD Card only */
+#define SDIO_SD_APP_SECURE_ERASE ((u8)38) /* For SD Card only */
+#define SDIO_SD_APP_CHANGE_SECURE_AREA ((u8)49) /* For SD Card only */
+#define SDIO_SD_APP_SECURE_WRITE_MKB ((u8)48) /* For SD Card only */
+
+typedef enum
+{
+ SD_NO_TRANSFER = 0,
+ SD_TRANSFER_IN_PROGRESS
+} SDTransferState;
+
+typedef struct
+{
+ u16 TransferredBytes;
+ SD_Error TransferError;
+ u8 padding;
+} SDLastTransferInfo;
+
+typedef struct /* Card Specific Data */
+{
+ vu8 CSDStruct; /* CSD structure */
+ vu8 SysSpecVersion; /* System specification version */
+ vu8 Reserved1; /* Reserved */
+ vu8 TAAC; /* Data read access-time 1 */
+ vu8 NSAC; /* Data read access-time 2 in CLK cycles */
+ vu8 MaxBusClkFrec; /* Max. bus clock frequency */
+ vu16 CardComdClasses; /* Card command classes */
+ vu8 RdBlockLen; /* Max. read data block length */
+ vu8 PartBlockRead; /* Partial blocks for read allowed */
+ vu8 WrBlockMisalign; /* Write block misalignment */
+ vu8 RdBlockMisalign; /* Read block misalignment */
+ vu8 DSRImpl; /* DSR implemented */
+ vu8 Reserved2; /* Reserved */
+ vu16 DeviceSize; /* Device Size */
+ vu8 MaxRdCurrentVDDMin; /* Max. read current @ VDD min */
+ vu8 MaxRdCurrentVDDMax; /* Max. read current @ VDD max */
+ vu8 MaxWrCurrentVDDMin; /* Max. write current @ VDD min */
+ vu8 MaxWrCurrentVDDMax; /* Max. write current @ VDD max */
+ vu8 DeviceSizeMul; /* Device size multiplier */
+ vu8 EraseGrSize; /* Erase group size */
+ vu8 EraseGrMul; /* Erase group size multiplier */
+ vu8 WrProtectGrSize; /* Write protect group size */
+ vu8 WrProtectGrEnable; /* Write protect group enable */
+ vu8 ManDeflECC; /* Manufacturer default ECC */
+ vu8 WrSpeedFact; /* Write speed factor */
+ vu8 MaxWrBlockLen; /* Max. write data block length */
+ vu8 WriteBlockPaPartial; /* Partial blocks for write allowed */
+ vu8 Reserved3; /* Reserded */
+ vu8 ContentProtectAppli; /* Content protection application */
+ vu8 FileFormatGrouop; /* File format group */
+ vu8 CopyFlag; /* Copy flag (OTP) */
+ vu8 PermWrProtect; /* Permanent write protection */
+ vu8 TempWrProtect; /* Temporary write protection */
+ vu8 FileFormat; /* File Format */
+ vu8 ECC; /* ECC code */
+ vu8 CSD_CRC; /* CSD CRC */
+ vu8 Reserved4; /* always 1*/
+} SD_CSD;
+
+typedef struct /*Card Identification Data*/
+{
+ vu8 ManufacturerID; /* ManufacturerID */
+ vu16 OEM_AppliID; /* OEM/Application ID */
+ vu32 ProdName1; /* Product Name part1 */
+ vu8 ProdName2; /* Product Name part2*/
+ vu8 ProdRev; /* Product Revision */
+ vu32 ProdSN; /* Product Serial Number */
+ vu8 Reserved1; /* Reserved1 */
+ vu16 ManufactDate; /* Manufacturing Date */
+ vu8 CID_CRC; /* CID CRC */
+ vu8 Reserved2; /* always 1 */
+} SD_CID;
+
+typedef struct
+{
+ SD_CSD SD_csd;
+ SD_CID SD_cid;
+ u8 CardType;
+ u16 RCA;
+} SD_CardInfo;
+
+/* Exported constants --------------------------------------------------------*/
+#define SD_DMA_MODE ((u32)0x00000000)
+#define SD_INTERRUPT_MODE ((u32)0x00000001)
+#define SD_POLLING_MODE ((u32)0x00000002)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+SD_Error SD_Init(void);
+SD_Error SD_PowerON(void);
+SD_Error SD_PowerOFF(void);
+SD_Error SD_InitializeCards(void);
+SD_Error SD_GetCardInfo(SD_CardInfo *cardinfo);
+SD_Error SD_EnableWideBusOperation(u32 WideMode);
+SD_Error SD_SetDeviceMode(u32 Mode);
+SD_Error SD_SelectDeselect(u32 addr);
+SD_Error SD_ReadBlock(u32 addr, u32 *readbuff, u16 BlockSize);
+SD_Error SD_ReadMultiBlocks(u32 addr, u32 *readbuff, u16 BlockSize, u32 NumberOfBlocks);
+SD_Error SD_WriteBlock(u32 addr, u32 *writebuff, u16 BlockSize);
+SD_Error SD_WriteMultiBlocks(u32 addr, u32 *writebuff, u16 BlockSize, u32 NumberOfBlocks);
+SDTransferState SD_GetTransferState(void);
+SD_Error SD_StopTransfer(void);
+SD_Error SD_Erase(u32 startaddr, u32 endaddr);
+SD_Error SD_SendStatus(u32 *pcardstatus);
+SD_Error SD_SendSDStatus(u32 *psdstatus);
+SD_Error SD_ProcessIRQSrc(void);
+
+#endif /* __SDCARD_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SDIO/stm32f10x_conf.h b/src/stm32lib/examples/SDIO/stm32f10x_conf.h new file mode 100755 index 0000000..f487d13 --- /dev/null +++ b/src/stm32lib/examples/SDIO/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SDIO/stm32f10x_it.c b/src/stm32lib/examples/SDIO/stm32f10x_it.c new file mode 100755 index 0000000..bf3e5b4 --- /dev/null +++ b/src/stm32lib/examples/SDIO/stm32f10x_it.c @@ -0,0 +1,745 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "sdcard.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+ /* Process All SDIO Interrupt Sources */
+ SD_ProcessIRQSrc();
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SDIO/stm32f10x_it.h b/src/stm32lib/examples/SDIO/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/SDIO/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/CRC/main.c b/src/stm32lib/examples/SPI/CRC/main.c new file mode 100755 index 0000000..72d3307 --- /dev/null +++ b/src/stm32lib/examples/SPI/CRC/main.c @@ -0,0 +1,326 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Local includes ------------------------------------------------------------*/
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define BufferSize 32
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+SPI_InitTypeDef SPI_InitStructure;
+u16 SPI1_Buffer_Tx[BufferSize] = {0x0102, 0x0304, 0x0506, 0x0708, 0x090A, 0x0B0C,
+ 0x0D0E, 0x0F10, 0x1112, 0x1314, 0x1516, 0x1718,
+ 0x191A, 0x1B1C, 0x1D1E, 0x1F20, 0x2122, 0x2324,
+ 0x2526, 0x2728, 0x292A, 0x2B2C, 0x2D2E, 0x2F30,
+ 0x3132, 0x3334, 0x3536, 0x3738, 0x393A, 0x3B3C,
+ 0x3D3E, 0x3F40};
+u16 SPI2_Buffer_Tx[BufferSize] = {0x5152, 0x5354, 0x5556, 0x5758, 0x595A, 0x5B5C,
+ 0x5D5E, 0x5F60, 0x6162, 0x6364, 0x6566, 0x6768,
+ 0x696A, 0x6B6C, 0x6D6E, 0x6F70, 0x7172, 0x7374,
+ 0x7576, 0x7778, 0x797A, 0x7B7C, 0x7D7E, 0x7F80,
+ 0x8182, 0x8384, 0x8586, 0x8788, 0x898A, 0x8B8C,
+ 0x8D8E, 0x8F90};
+u16 SPI1_Buffer_Rx[BufferSize], SPI2_Buffer_Rx[BufferSize];
+u8 TxIdx = 0, RxIdx = 0;
+vu16 CRC1Value = 0, CRC2Value = 0;
+volatile TestStatus TransferStatus1 = FAILED, TransferStatus2 = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private functions ---------------------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u16* pBuffer1, u16* pBuffer2, u16 BufferLength);
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* SPI1 configuration ------------------------------------------------------*/
+ SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
+ SPI_InitStructure.SPI_DataSize = SPI_DataSize_16b;
+ SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
+ SPI_InitStructure.SPI_CPHA = SPI_CPHA_2Edge;
+ SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
+ SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
+ SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
+ SPI_InitStructure.SPI_CRCPolynomial = 7;
+ SPI_Init(SPI1, &SPI_InitStructure);
+
+ /* SPI2 configuration ------------------------------------------------------*/
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Slave;
+ SPI_Init(SPI2, &SPI_InitStructure);
+
+ /* Enable SPI1 CRC calculation */
+ SPI_CalculateCRC(SPI1, ENABLE);
+ /* Enable SPI2 CRC calculation */
+ SPI_CalculateCRC(SPI2, ENABLE);
+
+ /* Enable SPI1 */
+ SPI_Cmd(SPI1, ENABLE);
+ /* Enable SPI2 */
+ SPI_Cmd(SPI2, ENABLE);
+
+ /* Transfer procedure */
+ while (TxIdx < BufferSize - 1)
+ {
+ /* Wait for SPI1 Tx buffer empty */
+ while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_TXE) == RESET);
+ /* Send SPI2 data */
+ SPI_I2S_SendData(SPI2, SPI2_Buffer_Tx[TxIdx]);
+ /* Send SPI1 data */
+ SPI_I2S_SendData(SPI1, SPI1_Buffer_Tx[TxIdx++]);
+ /* Wait for SPI2 data reception */
+ while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_RXNE) == RESET);
+ /* Read SPI2 received data */
+ SPI2_Buffer_Rx[RxIdx] = SPI_I2S_ReceiveData(SPI2);
+ /* Wait for SPI1 data reception */
+ while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_RXNE) == RESET);
+ /* Read SPI1 received data */
+ SPI1_Buffer_Rx[RxIdx++] = SPI_I2S_ReceiveData(SPI1);
+ }
+
+ /* Wait for SPI1 Tx buffer empty */
+ while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_TXE) == RESET);
+ /* Wait for SPI2 Tx buffer empty */
+ while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_TXE) == RESET);
+
+ /* Send last SPI2_Buffer_Tx data */
+ SPI_I2S_SendData(SPI2, SPI2_Buffer_Tx[TxIdx]);
+ /* Enable SPI2 CRC transmission */
+ SPI_TransmitCRC(SPI2);
+ /* Send last SPI1_Buffer_Tx data */
+ SPI_I2S_SendData(SPI1, SPI1_Buffer_Tx[TxIdx]);
+ /* Enable SPI1 CRC transmission */
+ SPI_TransmitCRC(SPI1);
+
+ /* Wait for SPI1 last data reception */
+ while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_RXNE) == RESET);
+ /* Read SPI1 last received data */
+ SPI1_Buffer_Rx[RxIdx] = SPI_I2S_ReceiveData(SPI1);
+
+ /* Wait for SPI2 last data reception */
+ while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_RXNE) == RESET);
+ /* Read SPI2 last received data */
+ SPI2_Buffer_Rx[RxIdx] = SPI_I2S_ReceiveData(SPI2);
+
+ /* Wait for SPI1 data reception: CRC transmitted by SPI2 */
+ while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_RXNE) == RESET);
+ /* Wait for SPI2 data reception: CRC transmitted by SPI1 */
+ while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_RXNE) == RESET);
+
+ /* Check the received data with the send ones */
+ TransferStatus1 = Buffercmp(SPI2_Buffer_Rx, SPI1_Buffer_Tx, BufferSize);
+ TransferStatus2 = Buffercmp(SPI1_Buffer_Rx, SPI2_Buffer_Tx, BufferSize);
+ /* TransferStatus1, TransferStatus2 = PASSED, if the data transmitted and received
+ are correct */
+ /* TransferStatus1, TransferStatus2 = FAILED, if the data transmitted and received
+ are different */
+
+ /* Test on the SPI1 CRC Error flag */
+ if ((SPI_I2S_GetFlagStatus(SPI1, SPI_FLAG_CRCERR)) == SET)
+ {
+ TransferStatus2 = FAILED;
+ }
+
+ /* Test on the SPI2 CRC Error flag */
+ if ((SPI_I2S_GetFlagStatus(SPI2, SPI_FLAG_CRCERR)) == SET)
+ {
+ TransferStatus1 = FAILED;
+ }
+
+ /* Read SPI1 received CRC value */
+ CRC1Value = SPI_I2S_ReceiveData(SPI1);
+ /* Read SPI2 received CRC value */
+ CRC2Value = SPI_I2S_ReceiveData(SPI2);
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK/2 */
+ RCC_PCLK2Config(RCC_HCLK_Div2);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* Enable peripheral clocks --------------------------------------------------*/
+ /* GPIOA, GPIOB and SPI1 clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB |
+ RCC_APB2Periph_SPI1, ENABLE);
+
+ /* SPI2 Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure SPI1 pins: SCK, MISO and MOSI ---------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5 | GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure SPI2 pins: SCK, MISO and MOSI ---------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u16* pBuffer1, u16* pBuffer2, u16 BufferLength)
+{
+ while (BufferLength--)
+ {
+ if (*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/CRC/readme.txt b/src/stm32lib/examples/SPI/CRC/readme.txt new file mode 100755 index 0000000..37df508 --- /dev/null +++ b/src/stm32lib/examples/SPI/CRC/readme.txt @@ -0,0 +1,86 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the SPI CRC Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to set a communication between two
+SPIs in full-duplex mode and performs a transfer from Master to Slave and
+Slave to Master followed by CRC transmission.
+
+SPI1 is configured as master and SPI2 as slave and both are in full-duplex
+configuration mode with 16bit data size and a 4.5Mbit/s communication speed.
+CRC calculation is enabled for both SPIs.
+
+After enabling both SPIs, the first data from SPI2_Buffer_Tx is transmitted from
+slave followed by the first data from SPI1_Buffer_Tx send by the master. A test
+on RxNE flag is done for both master and slave to check the reception of data on
+their respective data register. The same procedure is done for the remaining data
+to transfer except the last ones.
+
+Last data from SPI1_Buffer_Tx is transmitted followed by enabling CRC transmission
+for SPI1 and the last data from SPI2_Buffer_Tx is transmitted followed by enabling
+CRC transmission for SPI2: user must take care to reduce code on this phase for
+high speed communication.
+
+Last transmitted buffer data and CRC value are then received successively on
+master and slave data registers. The received CRC value are stored on CRC1Value
+and CRC2Value respectively for SPI1 and SPI2.
+
+Once the transfer is completed a comparison is done and TransferStatus1 and
+TransferStatus2 gives the data transfer status for each data transfer direction
+where it is PASSED if transmitted and received data are the same otherwise it
+is FAILED.
+A check of CRC error flag, for the master and the salve, is done after receiving
+CRC data.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+ - Connect SPI1 SCK (PA.05) pin to SPI2 SCK (PB.13) pin
+ - Connect SPI1 MISO (PA.06) pin to SPI2 MISO (PB.14) pin
+ - Connect SPI1 MOSI (PA.07) pin to SPI2 MOSI (PB.15) pin
+
+Note: in STM3210E-EVAL board, the jumper 14 (USB Disconnect) must be set in
+ position 1<->2 in order to not interfer with SPI2 MISO pin PB14.
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_spi.c
+ + stm32f10x_rcc.c
+ + stm32f10x_gpio.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/SPI/CRC/stm32f10x_conf.h b/src/stm32lib/examples/SPI/CRC/stm32f10x_conf.h new file mode 100755 index 0000000..7a25a6d --- /dev/null +++ b/src/stm32lib/examples/SPI/CRC/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+#define _SPI
+#define _SPI1
+#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+#define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/CRC/stm32f10x_it.c b/src/stm32lib/examples/SPI/CRC/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/SPI/CRC/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/CRC/stm32f10x_it.h b/src/stm32lib/examples/SPI/CRC/stm32f10x_it.h new file mode 100755 index 0000000..58da1cc --- /dev/null +++ b/src/stm32lib/examples/SPI/CRC/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/DMA/main.c b/src/stm32lib/examples/SPI/DMA/main.c new file mode 100755 index 0000000..8c332da --- /dev/null +++ b/src/stm32lib/examples/SPI/DMA/main.c @@ -0,0 +1,291 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define SPI2_DR_Address 0x4000380C
+#define BufferSize 32
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+SPI_InitTypeDef SPI_InitStructure;
+DMA_InitTypeDef DMA_InitStructure;
+GPIO_InitTypeDef GPIO_InitStructure;
+
+u8 SPI1_Buffer_Tx[BufferSize] = {0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09,
+ 0x0A, 0x0B, 0x0C, 0x0D, 0x0E, 0x0F, 0x10, 0x11, 0x12,
+ 0x13, 0x14, 0x15, 0x16, 0x17, 0x18, 0x19, 0x1A, 0x1B,
+ 0x1C, 0x1D, 0x1E, 0x1F, 0x20};
+u8 SPI2_Buffer_Rx[BufferSize];
+u8 TxIdx = 0;
+volatile TestStatus TransferStatus = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* DMA1 channel4 configuration ---------------------------------------------*/
+ DMA_DeInit(DMA1_Channel4);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)SPI2_DR_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)SPI2_Buffer_Rx;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = BufferSize;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA1_Channel4, &DMA_InitStructure);
+
+ /* SPI1 configuration ------------------------------------------------------*/
+ SPI_InitStructure.SPI_Direction = SPI_Direction_1Line_Tx;
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
+ SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
+ SPI_InitStructure.SPI_CPOL = SPI_CPOL_High;
+ SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge;
+ SPI_InitStructure.SPI_NSS = SPI_NSS_Hard;
+ SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_4;
+ SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
+ SPI_InitStructure.SPI_CRCPolynomial = 7;
+ SPI_Init(SPI1, &SPI_InitStructure);
+
+ /* SPI2 configuration ------------------------------------------------------*/
+ SPI_InitStructure.SPI_Direction = SPI_Direction_1Line_Rx;
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Slave;
+ SPI_Init(SPI2, &SPI_InitStructure);
+
+ /* Enable SPI1 NSS output for master mode */
+ SPI_SSOutputCmd(SPI1, ENABLE);
+
+ /* Enable SPI2 Rx request */
+ SPI_I2S_DMACmd(SPI2, SPI_I2S_DMAReq_Rx, ENABLE);
+
+ /* Enable SPI2 */
+ SPI_Cmd(SPI2, ENABLE);
+ /* Enable SPI1 */
+ SPI_Cmd(SPI1, ENABLE);
+
+ /* Enable DMA1 Channel4 */
+ DMA_Cmd(DMA1_Channel4, ENABLE);
+
+ /* Transfer procedure */
+ while (TxIdx < BufferSize)
+ {
+ /* Wait for SPI1 Tx buffer empty */
+ while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_TXE) == RESET);
+ /* Send SPI1 data */
+ SPI_I2S_SendData(SPI1, SPI1_Buffer_Tx[TxIdx++]);
+ }
+
+ /* Wait for DMA1 channel4 transfer complete */
+ while (!DMA_GetFlagStatus(DMA1_FLAG_TC4));
+
+ /* Check the corectness of written data */
+ TransferStatus = Buffercmp(SPI2_Buffer_Rx, SPI1_Buffer_Tx, BufferSize);
+ /* TransferStatus = PASSED, if the transmitted and received data
+ are equal */
+ /* TransferStatus = FAILED, if the transmitted and received data
+ are different */
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* Enable peripheral clocks --------------------------------------------------*/
+ /* DMA1 clock enable */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+
+ /* GPIOA, GPIOB and SPI1 clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB |
+ RCC_APB2Periph_SPI1, ENABLE);
+
+ /* SPI2 Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure SPI1 pins: NSS, SCK, MISO and MOSI ----------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure SPI2 pins: NSS, SCK, MISO and MOSI ----------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12 | GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength)
+{
+ while (BufferLength--)
+ {
+ if (*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/DMA/readme.txt b/src/stm32lib/examples/SPI/DMA/readme.txt new file mode 100755 index 0000000..dc709ba --- /dev/null +++ b/src/stm32lib/examples/SPI/DMA/readme.txt @@ -0,0 +1,72 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the SPI DMA Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to set a communication between the two
+SPIs in simplex mode and performs a transfer from Master in polling mode to the
+Slave in DMA receive mode. The NSS pin is managed by hardware.
+Both SPIs are configured with 8bit data frame and a 18Mbit/s communication speed.
+The dedicated DMA1 channel4 is configured for SPI2 Rx request to store received data
+in SPI2_Buffer_Rx. The master SPI1 is configured in bidirectional mode as transmitter
+only. The slave SPI2 is also configured in bidirectional but as receiver only.
+Both master and slave NSS pins are managed by hardware. The SS output is enabled
+for SPI1 to set it as a master and SPI2 as a slave.
+After transfering the first SPI1 data an SPI2 RxNE request on DMA1 channel4 is generated
+and the received data is stored in SPI2_Buffer_Rx. The same action is done for the rest
+of the buffer.
+Once the transfer is completed a comparison is done and TransferStatus gives the
+data transfer status where it is PASSED if transmitted and received data
+are the same otherwise it is FAILED.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+ - Connect SPI2 NSS pin (PB.12) to SPI1 NSS pin (PA.04)
+ - Connect SPI2 SCK pin (PB.13) to SPI1 SCK pin (PA.05)
+ - Connect SPI2 MISO pin (PB.14) to SPI1 MOSI pin (PA.07)
+
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_spi.c
+ + stm32f10x_rcc.c
+ + stm32f10x_gpio.c
+ + stm32f10x_dma.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/SPI/DMA/stm32f10x_conf.h b/src/stm32lib/examples/SPI/DMA/stm32f10x_conf.h new file mode 100755 index 0000000..2246d0e --- /dev/null +++ b/src/stm32lib/examples/SPI/DMA/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+#define _SPI
+#define _SPI1
+#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+#define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/DMA/stm32f10x_it.c b/src/stm32lib/examples/SPI/DMA/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/SPI/DMA/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/DMA/stm32f10x_it.h b/src/stm32lib/examples/SPI/DMA/stm32f10x_it.h new file mode 100755 index 0000000..58da1cc --- /dev/null +++ b/src/stm32lib/examples/SPI/DMA/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/main.c b/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/main.c new file mode 100755 index 0000000..95455d4 --- /dev/null +++ b/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/main.c @@ -0,0 +1,312 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Local includes ------------------------------------------------------------*/
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define BufferSize 32
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+SPI_InitTypeDef SPI_InitStructure;
+u8 SPI1_Buffer_Tx[BufferSize] = {0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09,
+ 0x0A, 0x0B, 0x0C, 0x0D, 0x0E, 0x0F, 0x10, 0x11, 0x12,
+ 0x13, 0x14, 0x15, 0x16, 0x17, 0x18, 0x19, 0x1A, 0x1B,
+ 0x1C, 0x1D, 0x1E, 0x1F, 0x20};
+u8 SPI2_Buffer_Tx[BufferSize] = {0x51, 0x52, 0x53, 0x54, 0x55, 0x56, 0x57, 0x58, 0x59,
+ 0x5A, 0x5B, 0x5C, 0x5D, 0x5E, 0x5F, 0x60, 0x61, 0x62,
+ 0x63, 0x64, 0x65, 0x66, 0x67, 0x68, 0x69, 0x6A, 0x6B,
+ 0x6C, 0x6D, 0x6E, 0x6F, 0x70};
+u8 SPI1_Buffer_Rx[BufferSize], SPI2_Buffer_Rx[BufferSize];
+u8 TxIdx = 0, RxIdx = 0, k = 0;
+volatile TestStatus TransferStatus1 = FAILED, TransferStatus2 = FAILED;
+volatile TestStatus TransferStatus3 = FAILED, TransferStatus4 = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private functions ---------------------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength);
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* 1st phase: SPI1 Master and SPI2 Slave */
+ /* SPI1 Config -------------------------------------------------------------*/
+ SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
+ SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
+ SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
+ SPI_InitStructure.SPI_CPHA = SPI_CPHA_2Edge;
+ SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
+ SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_4;
+ SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_LSB;
+ SPI_InitStructure.SPI_CRCPolynomial = 7;
+ SPI_Init(SPI1, &SPI_InitStructure);
+
+ /* SPI2 Config -------------------------------------------------------------*/
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Slave;
+ SPI_Init(SPI2, &SPI_InitStructure);
+
+ /* Enable SPI1 */
+ SPI_Cmd(SPI1, ENABLE);
+ /* Enable SPI2 */
+ SPI_Cmd(SPI2, ENABLE);
+
+ /* Transfer procedure */
+ while (TxIdx < BufferSize)
+ {
+ /* Wait for SPI1 Tx buffer empty */
+ while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_TXE) == RESET);
+ /* Send SPI2 data */
+ SPI_I2S_SendData(SPI2, SPI2_Buffer_Tx[TxIdx]);
+ /* Send SPI1 data */
+ SPI_I2S_SendData(SPI1, SPI1_Buffer_Tx[TxIdx++]);
+ /* Wait for SPI2 data reception */
+ while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_RXNE) == RESET);
+ /* Read SPI2 received data */
+ SPI2_Buffer_Rx[RxIdx] = SPI_I2S_ReceiveData(SPI2);
+ /* Wait for SPI1 data reception */
+ while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_RXNE) == RESET);
+ /* Read SPI1 received data */
+ SPI1_Buffer_Rx[RxIdx++] = SPI_I2S_ReceiveData(SPI1);
+ }
+
+ /* Check the corectness of written dada */
+ TransferStatus1 = Buffercmp(SPI2_Buffer_Rx, SPI1_Buffer_Tx, BufferSize);
+ TransferStatus2 = Buffercmp(SPI1_Buffer_Rx, SPI2_Buffer_Tx, BufferSize);
+ /* TransferStatus1, TransferStatus2 = PASSED, if the transmitted and received data
+ are equal */
+ /* TransferStatus1, TransferStatus2 = FAILED, if the transmitted and received data
+ are different */
+
+ /* 2nd phase: SPI1 Slave and SPI2 Master */
+ /* SPI1 Re-configuration ---------------------------------------------------*/
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Slave;
+ SPI_Init(SPI1, &SPI_InitStructure);
+
+ /* SPI2 Re-configuration ---------------------------------------------------*/
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
+ SPI_Init(SPI2, &SPI_InitStructure);
+
+ /* Reset TxIdx, RxIdx indexes and receive tables values */
+ TxIdx = 0;
+ RxIdx = 0;
+ for (k = 0; k < BufferSize; k++) SPI2_Buffer_Rx[k] = 0;
+ for (k = 0; k < BufferSize; k++) SPI1_Buffer_Rx[k] = 0;
+
+ /* Transfer procedure */
+ while (TxIdx < BufferSize)
+ {
+ /* Wait for SPI2 Tx buffer empty */
+ while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_TXE) == RESET);
+ /* Send SPI1 data */
+ SPI_I2S_SendData(SPI1, SPI1_Buffer_Tx[TxIdx]);
+ /* Send SPI2 data */
+ SPI_I2S_SendData(SPI2, SPI2_Buffer_Tx[TxIdx++]);
+ /* Wait for SPI1 data reception */
+ while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_RXNE) == RESET);
+ /* Read SPI1 received data */
+ SPI1_Buffer_Rx[RxIdx] = SPI_I2S_ReceiveData(SPI1);
+ /* Wait for SPI2 data reception */
+ while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_RXNE) == RESET);
+ /* Read SPI2 received data */
+ SPI2_Buffer_Rx[RxIdx++] = SPI_I2S_ReceiveData(SPI2);
+ }
+
+ /* Check the corectness of written dada */
+ TransferStatus3 = Buffercmp(SPI2_Buffer_Rx, SPI1_Buffer_Tx, BufferSize);
+ TransferStatus4 = Buffercmp(SPI1_Buffer_Rx, SPI2_Buffer_Tx, BufferSize);
+ /* TransferStatus3, TransferStatus4 = PASSED, if the transmitted and received data
+ are equal */
+ /* TransferStatus3, TransferStatus4 = FAILED, if the transmitted and received data
+ are different */
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK/2 */
+ RCC_PCLK2Config(RCC_HCLK_Div2);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* Enable peripheral clocks --------------------------------------------------*/
+ /* GPIOA, GPIOB and SPI1 clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB |
+ RCC_APB2Periph_SPI1, ENABLE);
+ /* SPI2 Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure SPI1 pins: SCK, MISO and MOSI ---------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5 | GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure SPI2 pins: SCK, MISO and MOSI ---------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures NVIC and Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength)
+{
+ while (BufferLength--)
+ {
+ if (*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {}
+}
+#endif
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/readme.txt b/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/readme.txt new file mode 100755 index 0000000..3909295 --- /dev/null +++ b/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/readme.txt @@ -0,0 +1,69 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the SPI FullDuplex_SoftNSS Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to set a communication between the two
+SPIs in full-duplex mode and performs a transfer from Master to Slave and then
+Slave to Master in the same application with software NSS management.
+Both SPIs are configured with 8bit data frame and a 9Mbit/s communication speed.
+In the first phase, the master SPI1 starts the SPI1_Buffer_Tx transfer while the
+slave SPI2 transmit SPI2_Buffer_Tx. Once the transfer is completed a comparison
+is done and TransferStatus1 and TransferStatus2 gives the data transfer status for
+each data transfer direction where it is PASSED if transmitted and received data
+are the same otherwise it is FAILED.
+As the NSS pin is managed by software, this permit to SPI1 to become slave and SPI2
+to become master whithout hardware modification
+In the second step, the slave SPI1 starts the SPI1_Buffer_Tx transfer while the
+master SPI2 transmit SPI2_Buffer_Tx. Once the transfer is completed a comparison
+is done and TransferStatus3 and TransferStatus4 gives the data transfer status for
+each data transfer direction where it is PASSED if transmitted and received data
+are the same otherwise it is FAILED.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+ - Connect SPI1 SCK pin (PA.05) to SPI2 SCK pin (PB.13)
+ - Connect SPI1 MISO pin (PA.06) to SPI2 MISO pin (PB.14)
+ - Connect SPI1 MOSI pin (PA.07) to SPI2 MOSI pin (PB.15)
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_spi.c
+ + stm32f10x_rcc.c
+ + stm32f10x_gpio.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/stm32f10x_conf.h b/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/stm32f10x_conf.h new file mode 100755 index 0000000..7a25a6d --- /dev/null +++ b/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+#define _SPI
+#define _SPI1
+#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+#define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/stm32f10x_it.c b/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/stm32f10x_it.h b/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/stm32f10x_it.h new file mode 100755 index 0000000..58da1cc --- /dev/null +++ b/src/stm32lib/examples/SPI/FullDuplex_SoftNSS/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/M25P64_FLASH/main.c b/src/stm32lib/examples/SPI/M25P64_FLASH/main.c new file mode 100755 index 0000000..b267d3d --- /dev/null +++ b/src/stm32lib/examples/SPI/M25P64_FLASH/main.c @@ -0,0 +1,264 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "platform_config.h"
+#include "spi_flash.h"
+
+/* Local includes ------------------------------------------------------------*/
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define FLASH_WriteAddress 0x700000
+#define FLASH_ReadAddress FLASH_WriteAddress
+#define FLASH_SectorToErase FLASH_WriteAddress
+#define M25P64_FLASH_ID 0x202017
+#define BufferSize (countof(Tx_Buffer)-1)
+
+/* Private macro -------------------------------------------------------------*/
+#define countof(a) (sizeof(a) / sizeof(*(a)))
+
+/* Private variables ---------------------------------------------------------*/
+u8 Tx_Buffer[] = "STM32F10x SPI Firmware Library Example: communication with an M25P64 SPI FLASH";
+u8 Index, Rx_Buffer[BufferSize];
+volatile TestStatus TransferStatus1 = FAILED, TransferStatus2 = PASSED;
+vu32 FLASH_ID = 0;
+ErrorStatus HSEStartUpStatus;
+
+/* Private functions ---------------------------------------------------------*/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength);
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* GPIO configuration */
+ GPIO_Configuration();
+
+ /* Initialize the SPI FLASH driver */
+ SPI_FLASH_Init();
+
+ /* Get SPI Flash ID */
+ FLASH_ID = SPI_FLASH_ReadID();
+ /* Check the SPI Flash ID */
+ if (FLASH_ID == M25P64_FLASH_ID)
+ {
+ /* OK: Set GPIO_LED pin 6 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_6, Bit_SET);
+ }
+ else
+ {
+ /* Error: Set GPIO_LED pin 7 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_7, Bit_SET);
+ }
+
+ /* Perform a write in the Flash followed by a read of the written data */
+ /* Erase SPI FLASH Sector to write on */
+ SPI_FLASH_SectorErase(FLASH_SectorToErase);
+
+ /* Write Tx_Buffer data to SPI FLASH memory */
+ SPI_FLASH_BufferWrite(Tx_Buffer, FLASH_WriteAddress, BufferSize);
+
+ /* Read data from SPI FLASH memory */
+ SPI_FLASH_BufferRead(Rx_Buffer, FLASH_ReadAddress, BufferSize);
+
+ /* Check the corectness of written dada */
+ TransferStatus1 = Buffercmp(Tx_Buffer, Rx_Buffer, BufferSize);
+ /* TransferStatus1 = PASSED, if the transmitted and received data by SPI1
+ are the same */
+ /* TransferStatus1 = FAILED, if the transmitted and received data by SPI1
+ are different */
+
+ /* Perform an erase in the Flash followed by a read of the written data */
+ /* Erase SPI FLASH Sector to write on */
+ SPI_FLASH_SectorErase(FLASH_SectorToErase);
+
+ /* Read data from SPI FLASH memory */
+ SPI_FLASH_BufferRead(Rx_Buffer, FLASH_ReadAddress, BufferSize);
+
+ /* Check the corectness of erasing operation dada */
+ for (Index = 0; Index < BufferSize; Index++)
+ {
+ if (Rx_Buffer[Index] != 0xFF)
+ {
+ TransferStatus2 = FAILED;
+ }
+ }
+ /* TransferStatus2 = PASSED, if the specified sector part is erased */
+ /* TransferStatus2 = FAILED, if the specified sector part is not well erased */
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* Enable GPIO_LED clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_LED, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure GPIO LED pin6 and pin7 as Output push-pull --------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength)
+{
+ while (BufferLength--)
+ {
+ if (*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {}
+}
+#endif
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/M25P64_FLASH/platform_config.h b/src/stm32lib/examples/SPI/M25P64_FLASH/platform_config.h new file mode 100755 index 0000000..3b73964 --- /dev/null +++ b/src/stm32lib/examples/SPI/M25P64_FLASH/platform_config.h @@ -0,0 +1,44 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+//#define USE_STM3210B_EVAL
+#define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/M25P64_FLASH/readme.txt b/src/stm32lib/examples/SPI/M25P64_FLASH/readme.txt new file mode 100755 index 0000000..d29c571 --- /dev/null +++ b/src/stm32lib/examples/SPI/M25P64_FLASH/readme.txt @@ -0,0 +1,99 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the SPI M25P64_Flash Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a basic example of how to use the SPI firmware library
+and an associate SPI FLASH driver to communicate with an M25P64 FLASH.
+
+The first step consist in reading the SPI Flash ID. A comparison between the ID
+read from SPI flash and the expected one is done and a specific GPIO pin is set
+in case of success otherwise this GPIO pin is reset.
+
+Using this driver the program performs an erase of the sector to be accessed, a
+write of a Tx_Buffer, defined in the main.c file, to the memory followed by a read
+of the written data. Then data read from the memory stored in the Rx_Buffer are
+compared with the expected values of the Tx_Buffer. The result of this comparison
+is stored in the "TransferStatus1" variable.
+
+A second erase of the same sector is done at the end, and a test is done to be
+sure that all the data written there are erased further to the sector erase. All
+the data location are read and checked with 0xFF value. The result of this test
+is stored in "TransferStatus2" variable which is FAILED in case of error.
+
+The SPI1 is configured as Master with an 8bits data size. A GPIO pin is used
+as output push-pull to drive the SPI Flash chip select pin.
+The FLASH_WriteAddress and the FLASH_ReadAddress where the program start the write
+and the read operations are defined in the main.c file.
+The system clock is set to 72MHz and SPI1 baudrate to 18 Mbit/s.
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+spi_flash.c SPI FLASH driver
+spi_flash.h Header for the spi_flash.c file
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h and spi_flash.h files.
+
+ + STM3210B-EVAL
+ - Use LD1 and LD2 leds connected respectively to PC.06 and PC.07 pins
+
+ + STM3210E-EVAL
+ - Use LD1 and LD2 leds connected respectively to PF.06 and PF.07 pins
+
+On the STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation boards, this
+SPI Flash is already available and there is no need to any extra hardware connections.
+
+If a different platform is used:
+ - Connect both SPI1 and SPI FLASH pins as following:
+ - Connect SPI1_NSS (PA.04) pin to SPI Flash chip select (pin1) and use the
+ STM3210B-EVAL hardware configuration defines.
+ - Connect SPI1_SCLK (PA.05) pin to SPI Flash serial clock (pin6).
+ - Connect SPI1_MISO (PA.06) pin to SPI Flash serial data output (pin2).
+ - Connect SPI1_MOSI (PA.07) pin to SPI Flash serial data input (pin5).
+ - Connect SPI Flash Write Protect (pin3) to Vdd
+ - Connect SPI Flash Hold (pin7) to Vdd
+ - Connect SPI Flash Vcc (pin8) to Vdd
+ - Connect SPI Flash Vss (pin4) to Vss
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_spi.c
+ + stm32f10x_rcc.c
+ + stm32f10x_gpio.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/SPI/M25P64_FLASH/spi_flash.c b/src/stm32lib/examples/SPI/M25P64_FLASH/spi_flash.c new file mode 100755 index 0000000..e19e7c1 --- /dev/null +++ b/src/stm32lib/examples/SPI/M25P64_FLASH/spi_flash.c @@ -0,0 +1,482 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : spi_flash.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file provides a set of functions needed to manage the
+* communication between SPI peripheral and SPI M25P64 FLASH.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "spi_flash.h"
+
+/* Private typedef -----------------------------------------------------------*/
+#define SPI_FLASH_PageSize 0x1006
+
+/* Private define ------------------------------------------------------------*/
+#define WRITE 0x02 /* Write to Memory instruction */
+#define WRSR 0x01 /* Write Status Register instruction */
+#define WREN 0x06 /* Write enable instruction */
+
+#define READ 0x03 /* Read from Memory instruction */
+#define RDSR 0x05 /* Read Status Register instruction */
+#define RDID 0x9F /* Read identification */
+#define SE 0xD8 /* Sector Erase instruction */
+#define BE 0xC7 /* Bulk Erase instruction */
+
+#define WIP_Flag 0x01 /* Write In Progress (WIP) flag */
+
+#define Dummy_Byte 0xA5
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : SPI_FLASH_Init
+* Description : Initializes the peripherals used by the SPI FLASH driver.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_FLASH_Init(void)
+{
+ SPI_InitTypeDef SPI_InitStructure;
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Enable SPI1 and GPIO clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1 | RCC_APB2Periph_GPIOA |
+ RCC_APB2Periph_GPIO_CS, ENABLE);
+
+ /* Configure SPI1 pins: SCK, MISO and MOSI */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5 | GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure I/O for Flash Chip select */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_CS;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_CS, &GPIO_InitStructure);
+
+ /* Deselect the FLASH: Chip Select high */
+ SPI_FLASH_CS_HIGH();
+
+ /* SPI1 configuration */
+ SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
+ SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
+ SPI_InitStructure.SPI_CPOL = SPI_CPOL_High;
+ SPI_InitStructure.SPI_CPHA = SPI_CPHA_2Edge;
+ SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
+ SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_4;
+ SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
+ SPI_InitStructure.SPI_CRCPolynomial = 7;
+ SPI_Init(SPI1, &SPI_InitStructure);
+
+ /* Enable SPI1 */
+ SPI_Cmd(SPI1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : SPI_FLASH_SectorErase
+* Description : Erases the specified FLASH sector.
+* Input : SectorAddr: address of the sector to erase.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_FLASH_SectorErase(u32 SectorAddr)
+{
+ /* Send write enable instruction */
+ SPI_FLASH_WriteEnable();
+
+ /* Sector Erase */
+ /* Select the FLASH: Chip Select low */
+ SPI_FLASH_CS_LOW();
+ /* Send Sector Erase instruction */
+ SPI_FLASH_SendByte(SE);
+ /* Send SectorAddr high nibble address byte */
+ SPI_FLASH_SendByte((SectorAddr & 0xFF0000) >> 16);
+ /* Send SectorAddr medium nibble address byte */
+ SPI_FLASH_SendByte((SectorAddr & 0xFF00) >> 8);
+ /* Send SectorAddr low nibble address byte */
+ SPI_FLASH_SendByte(SectorAddr & 0xFF);
+ /* Deselect the FLASH: Chip Select high */
+ SPI_FLASH_CS_HIGH();
+
+ /* Wait the end of Flash writing */
+ SPI_FLASH_WaitForWriteEnd();
+}
+
+/*******************************************************************************
+* Function Name : SPI_FLASH_BulkErase
+* Description : Erases the entire FLASH.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_FLASH_BulkErase(void)
+{
+ /* Send write enable instruction */
+ SPI_FLASH_WriteEnable();
+
+ /* Bulk Erase */
+ /* Select the FLASH: Chip Select low */
+ SPI_FLASH_CS_LOW();
+ /* Send Bulk Erase instruction */
+ SPI_FLASH_SendByte(BE);
+ /* Deselect the FLASH: Chip Select high */
+ SPI_FLASH_CS_HIGH();
+
+ /* Wait the end of Flash writing */
+ SPI_FLASH_WaitForWriteEnd();
+}
+
+/*******************************************************************************
+* Function Name : SPI_FLASH_PageWrite
+* Description : Writes more than one byte to the FLASH with a single WRITE
+* cycle(Page WRITE sequence). The number of byte can't exceed
+* the FLASH page size.
+* Input : - pBuffer : pointer to the buffer containing the data to be
+* written to the FLASH.
+* - WriteAddr : FLASH's internal address to write to.
+* - NumByteToWrite : number of bytes to write to the FLASH,
+* must be equal or less than "SPI_FLASH_PageSize" value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_FLASH_PageWrite(u8* pBuffer, u32 WriteAddr, u16 NumByteToWrite)
+{
+ /* Enable the write access to the FLASH */
+ SPI_FLASH_WriteEnable();
+
+ /* Select the FLASH: Chip Select low */
+ SPI_FLASH_CS_LOW();
+ /* Send "Write to Memory " instruction */
+ SPI_FLASH_SendByte(WRITE);
+ /* Send WriteAddr high nibble address byte to write to */
+ SPI_FLASH_SendByte((WriteAddr & 0xFF0000) >> 16);
+ /* Send WriteAddr medium nibble address byte to write to */
+ SPI_FLASH_SendByte((WriteAddr & 0xFF00) >> 8);
+ /* Send WriteAddr low nibble address byte to write to */
+ SPI_FLASH_SendByte(WriteAddr & 0xFF);
+
+ /* while there is data to be written on the FLASH */
+ while (NumByteToWrite--)
+ {
+ /* Send the current byte */
+ SPI_FLASH_SendByte(*pBuffer);
+ /* Point on the next byte to be written */
+ pBuffer++;
+ }
+
+ /* Deselect the FLASH: Chip Select high */
+ SPI_FLASH_CS_HIGH();
+
+ /* Wait the end of Flash writing */
+ SPI_FLASH_WaitForWriteEnd();
+}
+
+/*******************************************************************************
+* Function Name : SPI_FLASH_BufferWrite
+* Description : Writes block of data to the FLASH. In this function, the
+* number of WRITE cycles are reduced, using Page WRITE sequence.
+* Input : - pBuffer : pointer to the buffer containing the data to be
+* written to the FLASH.
+* - WriteAddr : FLASH's internal address to write to.
+* - NumByteToWrite : number of bytes to write to the FLASH.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_FLASH_BufferWrite(u8* pBuffer, u32 WriteAddr, u16 NumByteToWrite)
+{
+ u8 NumOfPage = 0, NumOfSingle = 0, Addr = 0, count = 0, temp = 0;
+
+ Addr = WriteAddr % SPI_FLASH_PageSize;
+ count = SPI_FLASH_PageSize - Addr;
+ NumOfPage = NumByteToWrite / SPI_FLASH_PageSize;
+ NumOfSingle = NumByteToWrite % SPI_FLASH_PageSize;
+
+ if (Addr == 0) /* WriteAddr is SPI_FLASH_PageSize aligned */
+ {
+ if (NumOfPage == 0) /* NumByteToWrite < SPI_FLASH_PageSize */
+ {
+ SPI_FLASH_PageWrite(pBuffer, WriteAddr, NumByteToWrite);
+ }
+ else /* NumByteToWrite > SPI_FLASH_PageSize */
+ {
+ while (NumOfPage--)
+ {
+ SPI_FLASH_PageWrite(pBuffer, WriteAddr, SPI_FLASH_PageSize);
+ WriteAddr += SPI_FLASH_PageSize;
+ pBuffer += SPI_FLASH_PageSize;
+ }
+
+ SPI_FLASH_PageWrite(pBuffer, WriteAddr, NumOfSingle);
+ }
+ }
+ else /* WriteAddr is not SPI_FLASH_PageSize aligned */
+ {
+ if (NumOfPage == 0) /* NumByteToWrite < SPI_FLASH_PageSize */
+ {
+ if (NumOfSingle > count) /* (NumByteToWrite + WriteAddr) > SPI_FLASH_PageSize */
+ {
+ temp = NumOfSingle - count;
+
+ SPI_FLASH_PageWrite(pBuffer, WriteAddr, count);
+ WriteAddr += count;
+ pBuffer += count;
+
+ SPI_FLASH_PageWrite(pBuffer, WriteAddr, temp);
+ }
+ else
+ {
+ SPI_FLASH_PageWrite(pBuffer, WriteAddr, NumByteToWrite);
+ }
+ }
+ else /* NumByteToWrite > SPI_FLASH_PageSize */
+ {
+ NumByteToWrite -= count;
+ NumOfPage = NumByteToWrite / SPI_FLASH_PageSize;
+ NumOfSingle = NumByteToWrite % SPI_FLASH_PageSize;
+
+ SPI_FLASH_PageWrite(pBuffer, WriteAddr, count);
+ WriteAddr += count;
+ pBuffer += count;
+
+ while (NumOfPage--)
+ {
+ SPI_FLASH_PageWrite(pBuffer, WriteAddr, SPI_FLASH_PageSize);
+ WriteAddr += SPI_FLASH_PageSize;
+ pBuffer += SPI_FLASH_PageSize;
+ }
+
+ if (NumOfSingle != 0)
+ {
+ SPI_FLASH_PageWrite(pBuffer, WriteAddr, NumOfSingle);
+ }
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_FLASH_BufferRead
+* Description : Reads a block of data from the FLASH.
+* Input : - pBuffer : pointer to the buffer that receives the data read
+* from the FLASH.
+* - ReadAddr : FLASH's internal address to read from.
+* - NumByteToRead : number of bytes to read from the FLASH.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_FLASH_BufferRead(u8* pBuffer, u32 ReadAddr, u16 NumByteToRead)
+{
+ /* Select the FLASH: Chip Select low */
+ SPI_FLASH_CS_LOW();
+
+ /* Send "Read from Memory " instruction */
+ SPI_FLASH_SendByte(READ);
+
+ /* Send ReadAddr high nibble address byte to read from */
+ SPI_FLASH_SendByte((ReadAddr & 0xFF0000) >> 16);
+ /* Send ReadAddr medium nibble address byte to read from */
+ SPI_FLASH_SendByte((ReadAddr& 0xFF00) >> 8);
+ /* Send ReadAddr low nibble address byte to read from */
+ SPI_FLASH_SendByte(ReadAddr & 0xFF);
+
+ while (NumByteToRead--) /* while there is data to be read */
+ {
+ /* Read a byte from the FLASH */
+ *pBuffer = SPI_FLASH_SendByte(Dummy_Byte);
+ /* Point to the next location where the byte read will be saved */
+ pBuffer++;
+ }
+
+ /* Deselect the FLASH: Chip Select high */
+ SPI_FLASH_CS_HIGH();
+}
+
+/*******************************************************************************
+* Function Name : SPI_FLASH_ReadID
+* Description : Reads FLASH identification.
+* Input : None
+* Output : None
+* Return : FLASH identification
+*******************************************************************************/
+u32 SPI_FLASH_ReadID(void)
+{
+ u32 Temp = 0, Temp0 = 0, Temp1 = 0, Temp2 = 0;
+
+ /* Select the FLASH: Chip Select low */
+ SPI_FLASH_CS_LOW();
+
+ /* Send "RDID " instruction */
+ SPI_FLASH_SendByte(0x9F);
+
+ /* Read a byte from the FLASH */
+ Temp0 = SPI_FLASH_SendByte(Dummy_Byte);
+
+ /* Read a byte from the FLASH */
+ Temp1 = SPI_FLASH_SendByte(Dummy_Byte);
+
+ /* Read a byte from the FLASH */
+ Temp2 = SPI_FLASH_SendByte(Dummy_Byte);
+
+ /* Deselect the FLASH: Chip Select high */
+ SPI_FLASH_CS_HIGH();
+
+ Temp = (Temp0 << 16) | (Temp1 << 8) | Temp2;
+
+ return Temp;
+}
+
+/*******************************************************************************
+* Function Name : SPI_FLASH_StartReadSequence
+* Description : Initiates a read data byte (READ) sequence from the Flash.
+* This is done by driving the /CS line low to select the device,
+* then the READ instruction is transmitted followed by 3 bytes
+* address. This function exit and keep the /CS line low, so the
+* Flash still being selected. With this technique the whole
+* content of the Flash is read with a single READ instruction.
+* Input : - ReadAddr : FLASH's internal address to read from.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_FLASH_StartReadSequence(u32 ReadAddr)
+{
+ /* Select the FLASH: Chip Select low */
+ SPI_FLASH_CS_LOW();
+
+ /* Send "Read from Memory " instruction */
+ SPI_FLASH_SendByte(READ);
+
+ /* Send the 24-bit address of the address to read from -----------------------*/
+ /* Send ReadAddr high nibble address byte */
+ SPI_FLASH_SendByte((ReadAddr & 0xFF0000) >> 16);
+ /* Send ReadAddr medium nibble address byte */
+ SPI_FLASH_SendByte((ReadAddr& 0xFF00) >> 8);
+ /* Send ReadAddr low nibble address byte */
+ SPI_FLASH_SendByte(ReadAddr & 0xFF);
+}
+
+/*******************************************************************************
+* Function Name : SPI_FLASH_ReadByte
+* Description : Reads a byte from the SPI Flash.
+* This function must be used only if the Start_Read_Sequence
+* function has been previously called.
+* Input : None
+* Output : None
+* Return : Byte Read from the SPI Flash.
+*******************************************************************************/
+u8 SPI_FLASH_ReadByte(void)
+{
+ return (SPI_FLASH_SendByte(Dummy_Byte));
+}
+
+/*******************************************************************************
+* Function Name : SPI_FLASH_SendByte
+* Description : Sends a byte through the SPI interface and return the byte
+* received from the SPI bus.
+* Input : byte : byte to send.
+* Output : None
+* Return : The value of the received byte.
+*******************************************************************************/
+u8 SPI_FLASH_SendByte(u8 byte)
+{
+ /* Loop while DR register in not emplty */
+ while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_TXE) == RESET);
+
+ /* Send byte through the SPI1 peripheral */
+ SPI_I2S_SendData(SPI1, byte);
+
+ /* Wait to receive a byte */
+ while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_RXNE) == RESET);
+
+ /* Return the byte read from the SPI bus */
+ return SPI_I2S_ReceiveData(SPI1);
+}
+
+/*******************************************************************************
+* Function Name : SPI_FLASH_SendHalfWord
+* Description : Sends a Half Word through the SPI interface and return the
+* Half Word received from the SPI bus.
+* Input : Half Word : Half Word to send.
+* Output : None
+* Return : The value of the received Half Word.
+*******************************************************************************/
+u16 SPI_FLASH_SendHalfWord(u16 HalfWord)
+{
+ /* Loop while DR register in not emplty */
+ while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_TXE) == RESET);
+
+ /* Send Half Word through the SPI1 peripheral */
+ SPI_I2S_SendData(SPI1, HalfWord);
+
+ /* Wait to receive a Half Word */
+ while (SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_RXNE) == RESET);
+
+ /* Return the Half Word read from the SPI bus */
+ return SPI_I2S_ReceiveData(SPI1);
+}
+
+/*******************************************************************************
+* Function Name : SPI_FLASH_WriteEnable
+* Description : Enables the write access to the FLASH.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_FLASH_WriteEnable(void)
+{
+ /* Select the FLASH: Chip Select low */
+ SPI_FLASH_CS_LOW();
+
+ /* Send "Write Enable" instruction */
+ SPI_FLASH_SendByte(WREN);
+
+ /* Deselect the FLASH: Chip Select high */
+ SPI_FLASH_CS_HIGH();
+}
+
+/*******************************************************************************
+* Function Name : SPI_FLASH_WaitForWriteEnd
+* Description : Polls the status of the Write In Progress (WIP) flag in the
+* FLASH's status register and loop until write opertaion
+* has completed.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_FLASH_WaitForWriteEnd(void)
+{
+ u8 FLASH_Status = 0;
+
+ /* Select the FLASH: Chip Select low */
+ SPI_FLASH_CS_LOW();
+
+ /* Send "Read Status Register" instruction */
+ SPI_FLASH_SendByte(RDSR);
+
+ /* Loop as long as the memory is busy with a write cycle */
+ do
+ {
+ /* Send a dummy byte to generate the clock needed by the FLASH
+ and put the value of the status register in FLASH_Status variable */
+ FLASH_Status = SPI_FLASH_SendByte(Dummy_Byte);
+
+ }
+ while ((FLASH_Status & WIP_Flag) == SET); /* Write in progress */
+
+ /* Deselect the FLASH: Chip Select high */
+ SPI_FLASH_CS_HIGH();
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/M25P64_FLASH/spi_flash.h b/src/stm32lib/examples/SPI/M25P64_FLASH/spi_flash.h new file mode 100755 index 0000000..9b7d569 --- /dev/null +++ b/src/stm32lib/examples/SPI/M25P64_FLASH/spi_flash.h @@ -0,0 +1,68 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : spi_flash.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Header for spi_flash.c file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __SPI_FLASH_H
+#define __SPI_FLASH_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_CS GPIOA
+ #define RCC_APB2Periph_GPIO_CS RCC_APB2Periph_GPIOA
+ #define GPIO_Pin_CS GPIO_Pin_4
+#else /* USE_STM3210E_EVAL */
+ #define GPIO_CS GPIOB
+ #define RCC_APB2Periph_GPIO_CS RCC_APB2Periph_GPIOB
+ #define GPIO_Pin_CS GPIO_Pin_2
+#endif
+
+/* Exported macro ------------------------------------------------------------*/
+/* Select SPI FLASH: Chip Select pin low */
+#define SPI_FLASH_CS_LOW() GPIO_ResetBits(GPIO_CS, GPIO_Pin_CS)
+/* Deselect SPI FLASH: Chip Select pin high */
+#define SPI_FLASH_CS_HIGH() GPIO_SetBits(GPIO_CS, GPIO_Pin_CS)
+
+/* Exported functions ------------------------------------------------------- */
+/*----- High layer function -----*/
+void SPI_FLASH_Init(void);
+void SPI_FLASH_SectorErase(u32 SectorAddr);
+void SPI_FLASH_BulkErase(void);
+void SPI_FLASH_PageWrite(u8* pBuffer, u32 WriteAddr, u16 NumByteToWrite);
+void SPI_FLASH_BufferWrite(u8* pBuffer, u32 WriteAddr, u16 NumByteToWrite);
+void SPI_FLASH_BufferRead(u8* pBuffer, u32 ReadAddr, u16 NumByteToRead);
+u32 SPI_FLASH_ReadID(void);
+void SPI_FLASH_StartReadSequence(u32 ReadAddr);
+
+/*----- Low layer function -----*/
+u8 SPI_FLASH_ReadByte(void);
+u8 SPI_FLASH_SendByte(u8 byte);
+u16 SPI_FLASH_SendHalfWord(u16 HalfWord);
+void SPI_FLASH_WriteEnable(void);
+void SPI_FLASH_WaitForWriteEnd(void);
+
+#endif /* __SPI_FLASH_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/M25P64_FLASH/stm32f10x_conf.h b/src/stm32lib/examples/SPI/M25P64_FLASH/stm32f10x_conf.h new file mode 100755 index 0000000..595dede --- /dev/null +++ b/src/stm32lib/examples/SPI/M25P64_FLASH/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+#define _SPI
+#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+#define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/M25P64_FLASH/stm32f10x_it.c b/src/stm32lib/examples/SPI/M25P64_FLASH/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/SPI/M25P64_FLASH/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/M25P64_FLASH/stm32f10x_it.h b/src/stm32lib/examples/SPI/M25P64_FLASH/stm32f10x_it.h new file mode 100755 index 0000000..58da1cc --- /dev/null +++ b/src/stm32lib/examples/SPI/M25P64_FLASH/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/Simplex_Interrupt/main.c b/src/stm32lib/examples/SPI/Simplex_Interrupt/main.c new file mode 100755 index 0000000..ab04041 --- /dev/null +++ b/src/stm32lib/examples/SPI/Simplex_Interrupt/main.c @@ -0,0 +1,274 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Local includes ------------------------------------------------------------*/
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define BufferSize 32
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+SPI_InitTypeDef SPI_InitStructure;
+u8 SPI1_Buffer_Tx[BufferSize] = {0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09,
+ 0x0A, 0x0B, 0x0C, 0x0D, 0x0E, 0x0F, 0x10, 0x11, 0x12,
+ 0x13, 0x14, 0x15, 0x16, 0x17, 0x18, 0x19, 0x1A, 0x1B,
+ 0x1C, 0x1D, 0x1E, 0x1F, 0x20};
+u8 SPI2_Buffer_Rx[BufferSize];
+vu8 TxIdx = 0, RxIdx = 0;
+volatile TestStatus TransferStatus = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private functions ---------------------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength);
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System clocks configuration ---------------------------------------------*/
+ RCC_Configuration();
+
+ /* NVIC configuration ------------------------------------------------------*/
+ NVIC_Configuration();
+
+ /* GPIO configuration ------------------------------------------------------*/
+ GPIO_Configuration();
+
+ /* SPI1 configuration ------------------------------------------------------*/
+ SPI_InitStructure.SPI_Direction = SPI_Direction_1Line_Tx;
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
+ SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
+ SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
+ SPI_InitStructure.SPI_CPHA = SPI_CPHA_2Edge;
+ SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
+ SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_4;
+ SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
+ SPI_InitStructure.SPI_CRCPolynomial = 7;
+ SPI_Init(SPI1, &SPI_InitStructure);
+
+ /* SPI2 configuration ------------------------------------------------------*/
+ SPI_InitStructure.SPI_Direction = SPI_Direction_1Line_Rx;
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Slave;
+ SPI_Init(SPI2, &SPI_InitStructure);
+
+ /* Enable SPI1 TXE interrupt */
+ SPI_I2S_ITConfig(SPI1, SPI_I2S_IT_TXE, ENABLE);
+ /* Enable SPI2 RXNE interrupt */
+ SPI_I2S_ITConfig(SPI2, SPI_I2S_IT_RXNE, ENABLE);
+
+ /* Enable SPI2 */
+ SPI_Cmd(SPI2, ENABLE);
+ /* Enable SPI1 */
+ SPI_Cmd(SPI1, ENABLE);
+
+ /* Transfer procedure */
+ while (RxIdx < BufferSize)
+ {}
+
+ /* Check the corectness of written dada */
+ TransferStatus = Buffercmp(SPI2_Buffer_Rx, SPI1_Buffer_Tx, BufferSize);
+ /* TransferStatus = PASSED, if the transmitted and received data
+ are equal */
+ /* TransferStatus = FAILED, if the transmitted and received data
+ are different */
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK/2 */
+ RCC_PCLK2Config(RCC_HCLK_Div2);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* Enable peripheral clocks --------------------------------------------------*/
+ /* GPIOA, GPIOB and SPI1 clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB |
+ RCC_APB2Periph_SPI1, ENABLE);
+
+ /* SPI2 Periph clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure SPI1 pins: SCK and MOSI ---------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure SPI2 pins: SCK and MISO ---------------------------------------*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13 | GPIO_Pin_14;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* 1 bit for pre-emption priority, 3 bits for subpriority */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
+
+ /* Configure and enable SPI1 interrupt -------------------------------------*/
+ NVIC_InitStructure.NVIC_IRQChannel = SPI1_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Configure and enable SPI2 interrupt -------------------------------------*/
+ NVIC_InitStructure.NVIC_IRQChannel = SPI2_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength)
+{
+ while (BufferLength--)
+ {
+ if (*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/Simplex_Interrupt/readme.txt b/src/stm32lib/examples/SPI/Simplex_Interrupt/readme.txt new file mode 100755 index 0000000..4f5d768 --- /dev/null +++ b/src/stm32lib/examples/SPI/Simplex_Interrupt/readme.txt @@ -0,0 +1,72 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the SPI Simplex_Intrerrupt Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to set a communication between two
+SPIs in simplex mode and performs a data buffer transfer from Master to Slave
+using TxE interrupt for master and RxNE interrupt for slave.
+
+Both SPIs are configured with 8bit data frame and a 9Mbit/s communication speed.
+SPI1 is configured to be a master transmitter and SPI2 as slave receiver.
+The TxE interrupt is enabled for the master and the RxNE interrupt is enabled for
+the slave.
+
+Once both SPIs are enabled, first TxE interrupt is generated for the master
+and in its interrupt service routine the first data is sent from SPI1_Buffer_Tx.
+Once this data is received by the slave a RxNE interrupt is generated and in the
+routine this data is stored in the SPI2_Buffer_Rx.
+
+The same procedure is followed for the remaining SPI1_Buffer_Tx data.
+Once all data buffer are received by the slave the TxE interrupt is disabled.
+A comparison is done and TransferStatus gives the data transfer status where
+it is PASSED if transmitted and received data are the same otherwise it is FAILED.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+ - Connect SPI1 SCK pin (PA.05) to SPI2 SCK pin (PB.13)
+ - Connect SPI1 MOSI pin (PA.07) to SPI2 MISO pin (PB.14)
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_spi.c
+ + stm32f10x_rcc.c
+ + stm32f10x_gpio.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/SPI/Simplex_Interrupt/stm32f10x_conf.h b/src/stm32lib/examples/SPI/Simplex_Interrupt/stm32f10x_conf.h new file mode 100755 index 0000000..7a25a6d --- /dev/null +++ b/src/stm32lib/examples/SPI/Simplex_Interrupt/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+#define _SPI
+#define _SPI1
+#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+#define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/Simplex_Interrupt/stm32f10x_it.c b/src/stm32lib/examples/SPI/Simplex_Interrupt/stm32f10x_it.c new file mode 100755 index 0000000..630574e --- /dev/null +++ b/src/stm32lib/examples/SPI/Simplex_Interrupt/stm32f10x_it.c @@ -0,0 +1,762 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define BufferSize 32
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+extern vu8 TxIdx, RxIdx;
+extern u8 SPI1_Buffer_Tx[BufferSize], SPI2_Buffer_Rx[BufferSize];
+
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+ if (SPI_I2S_GetITStatus(SPI1, SPI_I2S_IT_TXE) != RESET)
+ {
+ /* Send SPI1 data */
+ SPI_I2S_SendData(SPI1, SPI1_Buffer_Tx[TxIdx++]);
+
+ /* Disable SPI1 TXE interrupt */
+ if (TxIdx == BufferSize)
+ {
+ SPI_I2S_ITConfig(SPI1, SPI_I2S_IT_TXE, DISABLE);
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+ /* Store SPI2 received data */
+ SPI2_Buffer_Rx[RxIdx++] = SPI_I2S_ReceiveData(SPI2);
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SPI/Simplex_Interrupt/stm32f10x_it.h b/src/stm32lib/examples/SPI/Simplex_Interrupt/stm32f10x_it.h new file mode 100755 index 0000000..58da1cc --- /dev/null +++ b/src/stm32lib/examples/SPI/Simplex_Interrupt/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SysTick/main.c b/src/stm32lib/examples/SysTick/main.c new file mode 100755 index 0000000..53f0445 --- /dev/null +++ b/src/stm32lib/examples/SysTick/main.c @@ -0,0 +1,222 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+GPIO_InitTypeDef GPIO_InitStructure;
+static vu32 TimingDelay;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+void Delay(vu32 nTime);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* Configure GPIO_LED Pin 6, Pin 7, Pin 8 and Pin 9 as Output push-pull ----*/
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ /* Turn on Leds connected to GPIO_LED Pin 6 and Pin 8 */
+ GPIO_Write(GPIO_LED, GPIO_Pin_6 | GPIO_Pin_8);
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* SysTick end of count event each 1ms with input clock equal to 9MHz (HCLK/8, default) */
+ SysTick_SetReload(9000);
+
+ /* Enable SysTick interrupt */
+ SysTick_ITConfig(ENABLE);
+
+ while (1)
+ {
+ /* Toggle leds connected to GPIO_LED Pin 6, Pin 7, Pin 8 and Pin 9 */
+ GPIO_Write(GPIO_LED, (u16)~GPIO_ReadOutputData(GPIO_LED));
+
+ /* Insert 500 ms delay */
+ Delay(500);
+
+ /* Toggle leds connected to GPIO_LED Pin 6, Pin 7, Pin 8 and Pin 9 */
+ GPIO_Write(GPIO_LED, (u16)~GPIO_ReadOutputData(GPIO_LED));
+
+ /* Insert 300 ms delay */
+ Delay(300);
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable GPIO_LED clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_LED, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nTime: specifies the delay time length, in milliseconds.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(u32 nTime)
+{
+ /* Enable the SysTick Counter */
+ SysTick_CounterCmd(SysTick_Counter_Enable);
+
+ TimingDelay = nTime;
+
+ while(TimingDelay != 0);
+
+ /* Disable SysTick Counter */
+ SysTick_CounterCmd(SysTick_Counter_Disable);
+ /* Clear SysTick Counter */
+ SysTick_CounterCmd(SysTick_Counter_Clear);
+}
+
+/*******************************************************************************
+* Function Name : TimingDelay_Decrement
+* Description : Decrements the TimingDelay variable.
+* Input : None
+* Output : TimingDelay
+* Return : None
+*******************************************************************************/
+void TimingDelay_Decrement(void)
+{
+ if (TimingDelay != 0x00)
+ {
+ TimingDelay--;
+ }
+}
+
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SysTick/main.h b/src/stm32lib/examples/SysTick/main.h new file mode 100755 index 0000000..8342102 --- /dev/null +++ b/src/stm32lib/examples/SysTick/main.h @@ -0,0 +1,31 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Header for main.c module
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __MAIN_H
+#define __MAIN_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void TimingDelay_Decrement(void);
+
+#endif /* __MAIN_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SysTick/platform_config.h b/src/stm32lib/examples/SysTick/platform_config.h new file mode 100755 index 0000000..0bc5169 --- /dev/null +++ b/src/stm32lib/examples/SysTick/platform_config.h @@ -0,0 +1,44 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SysTick/readme.txt b/src/stm32lib/examples/SysTick/readme.txt new file mode 100755 index 0000000..7829a07 --- /dev/null +++ b/src/stm32lib/examples/SysTick/readme.txt @@ -0,0 +1,69 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the SysTick Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+
+This example shows how to configure the SysTick to generate a time base equal to
+1 ms. The system clock is set to 72 MHz, the SysTick is clocked by the AHB clock
+(HCLK) divided by 8.
+
+A "Delay" function is implemented based on the SysTick end-of-count event.
+Four LEDs connected to the GPIO_LED Pin 6, Pin 7, Pin 8 and Pin 9 are toggled
+with a timing defined by the Delay function.
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+main.h Header for main.c
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PC.06, PC.07, PC.08
+ and PC.09 pins
+
+ + STM3210E-EVAL
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PF.06, PF0.7, PF.08
+ and PF.09 pins
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_systick.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/SysTick/stm32f10x_conf.h b/src/stm32lib/examples/SysTick/stm32f10x_conf.h new file mode 100755 index 0000000..f421f9a --- /dev/null +++ b/src/stm32lib/examples/SysTick/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SysTick/stm32f10x_it.c b/src/stm32lib/examples/SysTick/stm32f10x_it.c new file mode 100755 index 0000000..3f1d5aa --- /dev/null +++ b/src/stm32lib/examples/SysTick/stm32f10x_it.c @@ -0,0 +1,812 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "main.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+ TimingDelay_Decrement();
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/SysTick/stm32f10x_it.h b/src/stm32lib/examples/SysTick/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/SysTick/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/6Steps/main.c b/src/stm32lib/examples/TIM/6Steps/main.c new file mode 100755 index 0000000..b20bf2e --- /dev/null +++ b/src/stm32lib/examples/TIM/6Steps/main.c @@ -0,0 +1,302 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+TIM_BDTRInitTypeDef TIM_BDTRInitStructure;
+u16 CCR1_Val = 32767;
+u16 CCR2_Val = 24575;
+u16 CCR3_Val = 16383;
+u16 CCR4_Val = 8191;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void SysTick_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* GPIO Configuration */
+ GPIO_Configuration();
+
+ /* SysTick Configuration */
+ SysTick_Configuration();
+
+ /*-----------------------------------------------------------------------------
+ The STM32F10x TIM1 peripheral offers the possibility to program in advance the
+ configuration for the next TIM1 outputs behaviour (step) and change the configuration
+ of all the channels at the same time. This operation is possible when the COM
+ (commutation) event is used.
+ The COM event can be generated by software by setting the COM bit in the TIM1_EGR
+ register or by hardware (on TRC rising edge).
+ In this example, a software COM event is generated each 100 ms: using the Systick
+ interrupt.
+ The TIM1 is configured in Timing Mode, each time a COM event occurs,
+ a new TIM1 configuration will be set in advance.
+ The following Table describes the TIM1 Channels states:
+ -----------------------------------------------
+ | Step1 | Step2 | Step3 | Step4 | Step5 | Step6 |
+ ----------------------------------------------------------
+ |Channel1 | 1 | 0 | 0 | 0 | 0 | 1 |
+ ----------------------------------------------------------
+ |Channel1N | 0 | 0 | 1 | 1 | 0 | 0 |
+ ----------------------------------------------------------
+ |Channel2 | 0 | 0 | 0 | 1 | 1 | 0 |
+ ----------------------------------------------------------
+ |Channel2N | 1 | 1 | 0 | 0 | 0 | 0 |
+ ----------------------------------------------------------
+ |Channel3 | 0 | 1 | 1 | 0 | 0 | 0 |
+ ----------------------------------------------------------
+ |Channel3N | 0 | 0 | 0 | 0 | 1 | 1 |
+ ----------------------------------------------------------
+ -----------------------------------------------------------------------------*/
+
+ /* Time Base configuration */
+ TIM_TimeBaseStructure.TIM_Prescaler = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseStructure.TIM_Period = 4095;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
+
+ TIM_TimeBaseInit(TIM1, &TIM_TimeBaseStructure);
+
+ /* Channel 1, 2,3 and 4 Configuration in PWM mode */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Timing;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = 2047;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
+ TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_High;
+ TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
+ TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Set;
+
+ TIM_OC1Init(TIM1, &TIM_OCInitStructure);
+
+ TIM_OCInitStructure.TIM_Pulse = 1023;
+ TIM_OC2Init(TIM1, &TIM_OCInitStructure);
+
+ TIM_OCInitStructure.TIM_Pulse = 511;
+ TIM_OC3Init(TIM1, &TIM_OCInitStructure);
+
+ /* Automatic Output enable, Break, dead time and lock configuration*/
+ TIM_BDTRInitStructure.TIM_OSSRState = TIM_OSSRState_Enable;
+ TIM_BDTRInitStructure.TIM_OSSIState = TIM_OSSIState_Enable;
+ TIM_BDTRInitStructure.TIM_LOCKLevel = TIM_LOCKLevel_OFF;
+ TIM_BDTRInitStructure.TIM_DeadTime = 1;
+ TIM_BDTRInitStructure.TIM_Break = TIM_Break_Enable;
+ TIM_BDTRInitStructure.TIM_BreakPolarity = TIM_BreakPolarity_High;
+ TIM_BDTRInitStructure.TIM_AutomaticOutput = TIM_AutomaticOutput_Enable;
+
+ TIM_BDTRConfig(TIM1, &TIM_BDTRInitStructure);
+
+ TIM_CCPreloadControl(TIM1, ENABLE);
+
+ TIM_ITConfig(TIM1, TIM_IT_COM, ENABLE);
+
+ /* TIM1 counter enable */
+ TIM_Cmd(TIM1, ENABLE);
+
+ /* Main Output Enable */
+ TIM_CtrlPWMOutputs(TIM1, ENABLE);
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* TIM1, GPIOA and GPIOB clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA |
+ RCC_APB2Periph_GPIOB, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the TIM1 Pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* GPIOA Configuration: Channel 1, 2 and 3 as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* GPIOB Configuration: Channel 1N, 2N and 3N as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* GPIOB Configuration: BKIN pin */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : SysTick_Configuration
+* Description : Configures the SysTick.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTick_Configuration(void)
+{
+ /* Configure SysTick to generate an interrupt each 100ms (with HCLK = 72MHz) -*/
+ /* Select AHB clock(HCLK) as SysTick clock source */
+ SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK);
+
+ /* SysTick interrupt each 10 Hz with Core clock equal to 72MHz */
+ SysTick_SetReload(7200000);
+
+ /* Enable SysTick Counter */
+ SysTick_CounterCmd(SysTick_Counter_Enable);
+
+ /* Enable SysTick interrupt */
+ SysTick_ITConfig(ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Enable the TIM1 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = TIM1_TRG_COM_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ NVIC_SystemHandlerPriorityConfig(SystemHandler_SysTick, 0, 0);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/6Steps/readme.txt b/src/stm32lib/examples/TIM/6Steps/readme.txt new file mode 100755 index 0000000..980d67e --- /dev/null +++ b/src/stm32lib/examples/TIM/6Steps/readme.txt @@ -0,0 +1,93 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM 6Steps example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to configure the TIM1 peripheral to generate 6 Steps.
+The STM32F10x TIM1 peripheral offers the possibility to program in advance the
+configuration for the next TIM1 outputs behaviour (step) and change the configuration
+of all the channels at the same time. This operation is possible when the COM
+(commutation) event is used.
+The COM event can be generated by software by setting the COM bit in the TIM1_EGR
+register or by hardware (on TRC rising edge).
+In this example, a software COM event is generated each 100 ms: using the SysTick
+interrupt.
+The TIM1 is configured in Timing Mode, each time a COM event occurs, a new TIM1
+configuration will be set in advance.
+
+The break Polarity is used at High level.
+
+The following Table describes the TIM1 Channels states:
+
+ -----------------------------------------------
+ | Step1 | Step2 | Step3 | Step4 | Step5 | Step6 |
+ ----------------------------------------------------------
+ |Channel1 | 1 | 0 | 0 | 0 | 0 | 1 |
+ ----------------------------------------------------------
+ |Channel1N | 0 | 0 | 1 | 1 | 0 | 0 |
+ ----------------------------------------------------------
+ |Channel2 | 0 | 0 | 0 | 1 | 1 | 0 |
+ ----------------------------------------------------------
+ |Channel2N | 1 | 1 | 0 | 0 | 0 | 0 |
+ ----------------------------------------------------------
+ |Channel3 | 0 | 1 | 1 | 0 | 0 | 0 |
+ ----------------------------------------------------------
+ |Channel3N | 0 | 0 | 0 | 0 | 1 | 1 |
+ ----------------------------------------------------------
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+- Connect the TIM1 pins to an oscilloscope to monitor the different waveforms:
+ - TIM1_CH3 pin (PA.10)
+ - TIM1_CH1N pin (PB.13)
+ - TIM1_CH2 pin (PA.09)
+ - TIM1_CH3N pin (PB.15)
+ - TIM1_CH1 pin (PA.08)
+ - TIM1_CH2N pin (PB.14)
+
+- Connect the TIM1 break pin TIM1_BKIN pin (PB.12) to the GND. To generate a break
+ event, switch this pin level from 0V to 3.3V.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_tim.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_systick.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/6Steps/stm32f10x_conf.h b/src/stm32lib/examples/TIM/6Steps/stm32f10x_conf.h new file mode 100755 index 0000000..75182b7 --- /dev/null +++ b/src/stm32lib/examples/TIM/6Steps/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/6Steps/stm32f10x_it.c b/src/stm32lib/examples/TIM/6Steps/stm32f10x_it.c new file mode 100755 index 0000000..d471afd --- /dev/null +++ b/src/stm32lib/examples/TIM/6Steps/stm32f10x_it.c @@ -0,0 +1,857 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+vu32 step = 1;
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+ /* Generate TIM1 COM event by software */
+ TIM_GenerateEvent(TIM1, TIM_EventSource_COM);
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+ /* Clear TIM1 COM pending bit */
+ TIM_ClearITPendingBit(TIM1, TIM_IT_COM);
+
+ if (step == 1)
+ {
+ /* Next step: Step 2 Configuration ---------------------------- */
+ /* Channel3 configuration */
+ TIM_CCxCmd(TIM1, TIM_Channel_3, TIM_CCx_Disable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_3, TIM_CCxN_Disable);
+
+ /* Channel1 configuration */
+ TIM_SelectOCxM(TIM1, TIM_Channel_1, TIM_ForcedAction_Active);
+ TIM_CCxCmd(TIM1, TIM_Channel_1, TIM_CCx_Enable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_1, TIM_CCxN_Enable);
+
+ /* Channel2 configuration */
+ TIM_SelectOCxM(TIM1, TIM_Channel_2, TIM_ForcedAction_InActive );
+ TIM_CCxCmd(TIM1, TIM_Channel_2, TIM_CCx_Enable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_2, TIM_CCxN_Enable);
+ step++;
+ }
+ else if (step == 2)
+ {
+ /* Next step: Step 3 Configuration ---------------------------- */
+ /* Channel2 configuration */
+ TIM_SelectOCxM(TIM1, TIM_Channel_2, TIM_ForcedAction_InActive);
+ TIM_CCxCmd(TIM1, TIM_Channel_2, TIM_CCx_Enable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_2, TIM_CCxN_Enable);
+
+ /* Channel3 configuration */
+ TIM_SelectOCxM(TIM1, TIM_Channel_3, TIM_ForcedAction_Active);
+ TIM_CCxCmd(TIM1, TIM_Channel_3, TIM_CCx_Enable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_3, TIM_CCxN_Enable);
+
+ /* Channel1 configuration */
+ TIM_CCxCmd(TIM1, TIM_Channel_1, TIM_CCx_Disable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_1, TIM_CCxN_Disable);
+ step++;
+ }
+ else if (step == 3)
+ {
+ /* Next step: Step 4 Configuration ---------------------------- */
+ /* Channel3 configuration */
+ TIM_SelectOCxM(TIM1, TIM_Channel_3, TIM_ForcedAction_Active);
+ TIM_CCxCmd(TIM1, TIM_Channel_3, TIM_CCx_Enable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_3, TIM_CCxN_Enable);
+
+ /* Channel2 configuration */
+ TIM_CCxCmd(TIM1, TIM_Channel_2, TIM_CCx_Disable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_2, TIM_CCxN_Disable);
+
+ /* Channel1 configuration */
+ TIM_SelectOCxM(TIM1, TIM_Channel_1, TIM_ForcedAction_InActive);
+ TIM_CCxCmd(TIM1, TIM_Channel_1, TIM_CCx_Enable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_1, TIM_CCxN_Enable);
+ step++;
+ }
+ else if (step == 4)
+ {
+ /* Next step: Step 5 Configuration ---------------------------- */
+ /* Channel3 configuration */
+ TIM_CCxCmd(TIM1, TIM_Channel_3, TIM_CCx_Disable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_3, TIM_CCxN_Disable);
+
+ /* Channel1 configuration */
+ TIM_SelectOCxM(TIM1, TIM_Channel_1, TIM_ForcedAction_InActive);
+ TIM_CCxCmd(TIM1, TIM_Channel_1, TIM_CCx_Enable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_1, TIM_CCxN_Enable);
+
+ /* Channel2 configuration */
+ TIM_SelectOCxM(TIM1, TIM_Channel_2, TIM_ForcedAction_Active);
+ TIM_CCxCmd(TIM1, TIM_Channel_2, TIM_CCx_Enable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_2, TIM_CCxN_Enable);
+ step++;
+ }
+ else if (step == 5)
+ {
+ /* Next step: Step 6 Configuration ---------------------------- */
+ /* Channel3 configuration */
+ TIM_SelectOCxM(TIM1, TIM_Channel_3, TIM_ForcedAction_InActive);
+ TIM_CCxCmd(TIM1, TIM_Channel_3, TIM_CCx_Enable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_3, TIM_CCxN_Enable);
+
+ /* Channel1 configuration */
+ TIM_CCxCmd(TIM1, TIM_Channel_1, TIM_CCx_Disable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_1, TIM_CCxN_Disable);
+
+ /* Channel2 configuration */
+ TIM_SelectOCxM(TIM1, TIM_Channel_2, TIM_ForcedAction_Active);
+ TIM_CCxCmd(TIM1, TIM_Channel_2, TIM_CCx_Enable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_2, TIM_CCxN_Enable);
+ step++;
+ }
+ else
+ {
+ /* Next step: Step 1 Configuration ---------------------------- */
+ /* Channel1 configuration */
+ TIM_SelectOCxM(TIM1, TIM_Channel_1, TIM_ForcedAction_Active);
+ TIM_CCxCmd(TIM1, TIM_Channel_1, TIM_CCx_Enable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_1, TIM_CCxN_Enable);
+
+ /* Channel3 configuration */
+ TIM_SelectOCxM(TIM1, TIM_Channel_3, TIM_ForcedAction_InActive);
+ TIM_CCxCmd(TIM1, TIM_Channel_3, TIM_CCx_Enable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_3, TIM_CCxN_Enable);
+
+ /* Channel2 configuration */
+ TIM_CCxCmd(TIM1, TIM_Channel_2, TIM_CCx_Disable);
+ TIM_CCxNCmd(TIM1, TIM_Channel_2, TIM_CCxN_Disable);
+ step = 1;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/6Steps/stm32f10x_it.h b/src/stm32lib/examples/TIM/6Steps/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/6Steps/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/7PWM_Output/main.c b/src/stm32lib/examples/TIM/7PWM_Output/main.c new file mode 100755 index 0000000..a400c2e --- /dev/null +++ b/src/stm32lib/examples/TIM/7PWM_Output/main.c @@ -0,0 +1,228 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+u16 CCR1_Val = 2047;
+u16 CCR2_Val = 1535;
+u16 CCR3_Val = 1023;
+u16 CCR4_Val = 511;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* GPIO Configuration */
+ GPIO_Configuration();
+
+ /* TIM1 Configuration ---------------------------------------------------
+ Generates 7 PWM signals with 4 different duty cycles:
+ TIM1CLK = 72 MHz, Prescaler = 0, TIM1 counter clock = 72 MHz
+ TIM1 frequency = TIM1CLK/(TIM1_Period + 1) = 17.57 KHz
+ - TIM1 Channel1 & Channel1N duty cycle = TIM1->CCR1 / (TIM1_Period + 1) = 50%
+ - TIM1 Channel2 & Channel2N duty cycle = TIM1->CCR2 / (TIM1_Period + 1) = 37.5%
+ - TIM1 Channel3 & Channel3N duty cycle = TIM1->CCR3 / (TIM1_Period + 1) = 25%
+ - TIM1 Channel4 duty cycle = TIM1->CCR4 / (TIM1_Period + 1) = 12.5%
+ ----------------------------------------------------------------------- */
+
+ /* Time Base configuration */
+ TIM_TimeBaseStructure.TIM_Prescaler = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseStructure.TIM_Period = 4095;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
+
+ TIM_TimeBaseInit(TIM1, &TIM_TimeBaseStructure);
+
+ /* Channel 1, 2,3 and 4 Configuration in PWM mode */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR1_Val;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low;
+ TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_High;
+ TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
+ TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCIdleState_Reset;
+
+ TIM_OC1Init(TIM1, &TIM_OCInitStructure);
+
+ TIM_OCInitStructure.TIM_Pulse = CCR2_Val;
+ TIM_OC2Init(TIM1, &TIM_OCInitStructure);
+
+ TIM_OCInitStructure.TIM_Pulse = CCR3_Val;
+ TIM_OC3Init(TIM1, &TIM_OCInitStructure);
+
+ TIM_OCInitStructure.TIM_Pulse = CCR4_Val;
+ TIM_OC4Init(TIM1, &TIM_OCInitStructure);
+
+ /* TIM1 counter enable */
+ TIM_Cmd(TIM1, ENABLE);
+
+ /* TIM1 Main Output Enable */
+ TIM_CtrlPWMOutputs(TIM1, ENABLE);
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* TIM1, GPIOA and GPIOB clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA |
+ RCC_APB2Periph_GPIOB, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the TIM1 Pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* GPIOA Configuration: Channel 1, 2, 3 and 4 as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10 | GPIO_Pin_11;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* GPIOB Configuration: Channel 1N, 2N and 3N as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/7PWM_Output/readme.txt b/src/stm32lib/examples/TIM/7PWM_Output/readme.txt new file mode 100755 index 0000000..950ac44 --- /dev/null +++ b/src/stm32lib/examples/TIM/7PWM_Output/readme.txt @@ -0,0 +1,90 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM 7PWM_Output example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+
+This example shows how to configure the TIM1 peripheral to generate 7 PWM signals
+with 4 different duty cycles.
+
+TIM1CLK is fixed to 72 MHz, the TIM1 Prescaler is equal to 0 so the TIM1 counter
+clock used is 72 MHz.
+
+TIM1 frequency is defined as follow:
+TIM1 frequency = TIM1CLK/(TIM1_Period + 1) = 17.57 KHz.
+
+The TIM1 CCR1 register value is equal to 0x7FF, so the TIM1 Channel 1 and TIM1
+Channel 1N generate a PWM signal with a frequency equal to 17.57 KHz
+and a duty cycle equal to:
+TIM1 Channel1 duty cycle = TIM1_CCR1 /( TIM1_Period + 1) = 50%.
+
+The TIM1 CCR2 register value is equal to 0x5FF, so the TIM1 Channel 2 and TIM1
+Channel 2N generate a PWM signal with a frequency equal to 17.57 KHz
+and a duty cycle equal to:
+TIM1 Channel2 duty cycle = TIM1_CCR2 / ( TIM1_Period + 1)= 37.5%.
+
+The TIM1 CCR3 register value is equal to 0x3FF, so the TIM1 Channel 3 and TIM1
+Channel 3N generate a PWM signal with a frequency equal to 17.57 KHz
+and a duty cycle equal to:
+TIM1 Channel3 duty cycle = TIM1_CCR3 / ( TIM1_Period + 1) = 25%.
+
+The TIM1 CCR4 register value is equal to 0x1FF, so the TIM1 Channel 4
+generate a PWM signal with a frequency equal to 17.57 KHz
+and a duty cycle equal to:
+TIM1 Channel4 duty cycle = TIM1_CCR4 / ( TIM1_Period + 1) = 12.5%.
+
+The TIM1 waveform can be displayed using an oscilloscope.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+Connect the TIM1 pins to an oscilloscope to monitor the different waveforms:
+ - TIM1_CH1 pin (PA.08)
+ - TIM1_CH1N pin (PB.13)
+ - TIM1_CH2 pin (PA.09)
+ - TIM1_CH2N pin (PB.14)
+ - TIM1_CH3 pin (PA.10)
+ - TIM1_CH3N pin (PB.15)
+ - TIM1_CH4 pin (PA.11)
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_tim.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/7PWM_Output/stm32f10x_conf.h b/src/stm32lib/examples/TIM/7PWM_Output/stm32f10x_conf.h new file mode 100755 index 0000000..d277318 --- /dev/null +++ b/src/stm32lib/examples/TIM/7PWM_Output/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/7PWM_Output/stm32f10x_it.c b/src/stm32lib/examples/TIM/7PWM_Output/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/TIM/7PWM_Output/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/7PWM_Output/stm32f10x_it.h b/src/stm32lib/examples/TIM/7PWM_Output/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/7PWM_Output/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/Cascade_Synchro/main.c b/src/stm32lib/examples/TIM/Cascade_Synchro/main.c new file mode 100755 index 0000000..4dfce78 --- /dev/null +++ b/src/stm32lib/examples/TIM/Cascade_Synchro/main.c @@ -0,0 +1,272 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* GPIO Configuration */
+ GPIO_Configuration();
+
+ /* Timers synchronisation in cascade mode ----------------------------
+ 1/TIM2 is configured as Master Timer:
+ - PWM Mode is used
+ - The TIM2 Update event is used as Trigger Output
+
+ 2/TIM3 is slave for TIM2 and Master for TIM4,
+ - PWM Mode is used
+ - The ITR1(TIM2) is used as input trigger
+ - Gated mode is used, so start and stop of slave counter
+ are controlled by the Master trigger output signal(TIM2 update event).
+ - The TIM3 Update event is used as Trigger Output.
+
+ 3/TIM4 is slave for TIM3,
+ - PWM Mode is used
+ - The ITR2(TIM3) is used as input trigger
+ - Gated mode is used, so start and stop of slave counter
+ are controlled by the Master trigger output signal(TIM3 update event).
+
+ The TIMxCLK is fixed to 72 MHz, the TIM2 counter clock is 72 MHz.
+
+ The Master Timer TIM2 is running at TIM2 frequency :
+ TIM2 frequency = (TIM2 counter clock)/ (TIM2 period + 1) = 281.250 KHz
+ and the duty cycle = TIM2_CCR1/(TIM2_ARR + 1) = 25%.
+
+ The TIM3 is running:
+ - At (TIM2 frequency)/ (TIM3 period + 1) = 70.312 KHz and a duty cycle
+ equal to TIM3_CCR1/(TIM3_ARR + 1) = 25%
+
+ The TIM4 is running:
+ - At (TIM3 frequency)/ (TIM4 period + 1) = 17.578 KHz and a duty cycle
+ equal to TIM4_CCR1/(TIM4_ARR + 1) = 25%
+ -------------------------------------------------------------------- */
+
+ /* Time base configuration */
+ TIM_TimeBaseStructure.TIM_Period = 255;
+ TIM_TimeBaseStructure.TIM_Prescaler = 0;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+
+ TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
+
+ TIM_TimeBaseStructure.TIM_Period = 3;
+ TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
+
+ TIM_TimeBaseStructure.TIM_Period = 3;
+ TIM_TimeBaseInit(TIM4, &TIM_TimeBaseStructure);
+
+ /* Master Configuration in PWM1 Mode */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = 64;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
+
+ TIM_OC1Init(TIM2, &TIM_OCInitStructure);
+
+ /* Select the Master Slave Mode */
+ TIM_SelectMasterSlaveMode(TIM2, TIM_MasterSlaveMode_Enable);
+
+ /* Master Mode selection */
+ TIM_SelectOutputTrigger(TIM2, TIM_TRGOSource_Update);
+
+ /* Slaves Configuration: PWM1 Mode */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = 1;
+
+ TIM_OC1Init(TIM3, &TIM_OCInitStructure);
+
+ TIM_OC1Init(TIM4, &TIM_OCInitStructure);
+
+ /* Slave Mode selection: TIM3 */
+ TIM_SelectSlaveMode(TIM3, TIM_SlaveMode_Gated);
+ TIM_SelectInputTrigger(TIM3, TIM_TS_ITR1);
+
+ /* Select the Master Slave Mode */
+ TIM_SelectMasterSlaveMode(TIM3, TIM_MasterSlaveMode_Enable);
+
+ /* Master Mode selection: TIM3 */
+ TIM_SelectOutputTrigger(TIM3, TIM_TRGOSource_Update);
+
+ /* Slave Mode selection: TIM4 */
+ TIM_SelectSlaveMode(TIM4, TIM_SlaveMode_Gated);
+ TIM_SelectInputTrigger(TIM4, TIM_TS_ITR2);
+
+ /* TIM enable counter */
+ TIM_Cmd(TIM3, ENABLE);
+ TIM_Cmd(TIM2, ENABLE);
+ TIM_Cmd(TIM4, ENABLE);
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+ /* TIM2, TIM3 and TIM4 clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 |
+ RCC_APB1Periph_TIM4, ENABLE);
+
+
+ /* GPIOA and GPIOB clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the GPIOD Pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* GPIOA Configuration: PA0(TIM2 CH1) and PA6(TIM3 CH1) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_6;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* GPIOB Configuration: PB6(TIM4 CH1) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
+
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/Cascade_Synchro/readme.txt b/src/stm32lib/examples/TIM/Cascade_Synchro/readme.txt new file mode 100755 index 0000000..110a40d --- /dev/null +++ b/src/stm32lib/examples/TIM/Cascade_Synchro/readme.txt @@ -0,0 +1,91 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM Cascade_Synchro example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+
+This example shows how to synchronize TIM peripherals in cascade mode.
+In this example three timers are used:
+
+Timers synchronisation in cascade mode:
+1/TIM2 is configured as Master Timer:
+ - PWM Mode is used
+ - The TIM2 Update event is used as Trigger Output
+
+2/TIM3 is slave for TIM2 and Master for TIM4,
+ - PWM Mode is used
+ - The ITR1(TIM2) is used as input trigger
+ - Gated mode is used, so start and stop of slave counter
+ are controlled by the Master trigger output signal(TIM2 update event).
+ - The TIM3 Update event is used as Trigger Output.
+
+3/TIM4 is slave for TIM3,
+ - PWM Mode is used
+ - The ITR2(TIM3) is used as input trigger
+ - Gated mode is used, so start and stop of slave counter are controlled by the
+ Master trigger output signal(TIM3 update event).
+
+The TIMxCLK is fixed to 72 MHz, the TIM2 counter clock is 72 MHz.
+The Master Timer TIM2 is running at TIM2 frequency :
+TIM2 frequency = (TIM2 counter clock)/ (TIM2 period + 1) = 281.250 KHz
+and the duty cycle = TIM2_CCR1/(TIM2_ARR + 1) = 25%.
+
+The TIM3 is running:
+ - At (TIM2 frequency)/ (TIM3 period + 1) = 70.312 KHz and a duty cycle equal
+to TIM3_CCR1/(TIM3_ARR + 1) = 25%
+
+The TIM4 is running:
+ - At (TIM3 frequency)/ (TIM4 period + 1) = 17.578 Hz and a duty cycle equal
+to TIM4_CCR1/(TIM4_ARR + 1) = 25%
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+Connect the
+- TIM2 CH1 (PA.00)
+- TIM3 CH1 (PA.06)
+- TIM4 CH1 (PB.06)
+pins to an oscilloscope to monitor the different waveforms
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_tim.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/Cascade_Synchro/stm32f10x_conf.h b/src/stm32lib/examples/TIM/Cascade_Synchro/stm32f10x_conf.h new file mode 100755 index 0000000..6a1768b --- /dev/null +++ b/src/stm32lib/examples/TIM/Cascade_Synchro/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+#define _TIM2
+#define _TIM3
+#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/Cascade_Synchro/stm32f10x_it.c b/src/stm32lib/examples/TIM/Cascade_Synchro/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/TIM/Cascade_Synchro/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/Cascade_Synchro/stm32f10x_it.h b/src/stm32lib/examples/TIM/Cascade_Synchro/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/Cascade_Synchro/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/ComplementarySignals/main.c b/src/stm32lib/examples/TIM/ComplementarySignals/main.c new file mode 100755 index 0000000..6fa0f26 --- /dev/null +++ b/src/stm32lib/examples/TIM/ComplementarySignals/main.c @@ -0,0 +1,253 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+TIM_BDTRInitTypeDef TIM_BDTRInitStructure;
+u16 CCR1_Val = 32767;
+u16 CCR2_Val = 16383;
+u16 CCR3_Val = 8191;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* GPIO Configuration */
+ GPIO_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* -----------------------------------------------------------------------
+ TIM1 Configuration to:
+
+ 1/ Generate 3 complementary PWM signals with 3 different duty cycles:
+ TIM1CLK = 72 MHz, Prescaler = 0, TIM1 counter clock = 72 MHz
+ TIM1 frequency = TIM1CLK/(TIM1_Period + 1) = 1.098 KHz
+
+ TIM1 Channel1 duty cycle = TIM1->CCR1 / TIM1_Period = 50%
+ TIM1 Channel1N duty cycle = (TIM1_Period - TIM1_CCR1) / (TIM1_Period + 1) = 50%
+
+ TIM1 Channel2 duty cycle = TIM1_CCR2 / TIM1_Period = 25%
+ TIM1 Channel2N duty cycle = (TIM1_Period - TIM1_CCR1) / (TIM1_Period + 1) = 75%
+
+ TIM1 Channel3 duty cycle = TIM1_CCR3 / TIM1_Period = 12.5%
+ TIM1 Channel3N duty cycle = (TIM1_Period - TIM1_CCR3) / (TIM1_Period + 1) = 87.5%
+
+ 2/ Insert a dead time equal to 1.62 us
+ 3/ Configure the break feature, active at High level, and using the automatic
+ output enable feature
+ 4/ Use the Locking parametres level1.
+ ----------------------------------------------------------------------- */
+
+ /* Time Base configuration */
+ TIM_TimeBaseStructure.TIM_Prescaler = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseStructure.TIM_Period = 65535;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
+
+ TIM_TimeBaseInit(TIM1, &TIM_TimeBaseStructure);
+
+ /* Channel 1, 2,3 and 4 Configuration in PWM mode */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR1_Val;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low;
+ TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_Low;
+ TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
+ TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCIdleState_Reset;
+
+ TIM_OC1Init(TIM1, &TIM_OCInitStructure);
+
+ TIM_OCInitStructure.TIM_Pulse = CCR2_Val;
+ TIM_OC2Init(TIM1, &TIM_OCInitStructure);
+
+ TIM_OCInitStructure.TIM_Pulse = CCR3_Val;
+ TIM_OC3Init(TIM1, &TIM_OCInitStructure);
+
+ /* Automatic Output enable, Break, dead time and lock configuration*/
+ TIM_BDTRInitStructure.TIM_OSSRState = TIM_OSSRState_Enable;
+ TIM_BDTRInitStructure.TIM_OSSIState = TIM_OSSIState_Enable;
+ TIM_BDTRInitStructure.TIM_LOCKLevel = TIM_LOCKLevel_1;
+ TIM_BDTRInitStructure.TIM_DeadTime = 117;
+ TIM_BDTRInitStructure.TIM_Break = TIM_Break_Enable;
+ TIM_BDTRInitStructure.TIM_BreakPolarity = TIM_BreakPolarity_High;
+ TIM_BDTRInitStructure.TIM_AutomaticOutput = TIM_AutomaticOutput_Enable;
+
+ TIM_BDTRConfig(TIM1, &TIM_BDTRInitStructure);
+
+ /* TIM1 counter enable */
+ TIM_Cmd(TIM1, ENABLE);
+
+ /* Main Output Enable */
+ TIM_CtrlPWMOutputs(TIM1, ENABLE);
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* TIM1, GPIOA and GPIOB clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA |
+ RCC_APB2Periph_GPIOB, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the TIM1 Pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* GPIOA Configuration: TIM1 Channel 1, 2 and 3 as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* GPIOB Configuration: TIM1 Channel 1N, 2N and 3N as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* GPIOB Configuration: BKIN pin */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/ComplementarySignals/readme.txt b/src/stm32lib/examples/TIM/ComplementarySignals/readme.txt new file mode 100755 index 0000000..654755a --- /dev/null +++ b/src/stm32lib/examples/TIM/ComplementarySignals/readme.txt @@ -0,0 +1,87 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM ComplementarySignals example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to configure the TIM1 peripheral to generate three
+complementary TIM1 signals, to insert a defined dead time value, to use the break
+feature and to lock the desired parameters.
+
+TIM1CLK is fixed to 72 MHz, the TIM1 Prescaler is equal to 0 so the TIM1 counter
+clock used is 72 MHz.
+
+TIM1 frequency is defined as follow:
+TIM1 frequency = TIM1 counter clock / (TIM1_Period + 1) = 1.098 KHz.
+
+The Three Duty cycles are computed as the following description:
+
+TIM1 Channel1 duty cycle = TIM1_CCR1 / (TIM1_Period + 1) = 50%
+TIM1 Channel1N duty cycle = (TIM1_Period - TIM1_CCR1) / (TIM1_Period + 1) = 50%
+
+TIM1 Channel2 duty cycle = TIM1_CCR2 / (TIM1_Period + 1) = 25%
+TIM1 Channel2N duty cycle = (TIM1_Period - TIM1_CCR1) / (TIM1_Period + 1) = 75%
+
+TIM1 Channel3 duty cycle = TIM1_CCR3 / TIM1_Period = 12.5%
+TIM1 Channel3N duty cycle = (TIM1_Period - TIM1_CCR3) / (TIM1_Period + 1) = 87.5%
+
+A dead time of 1.62 us is inserted between the different complementary signals,
+and the Lock level 1 is selected.
+The break Polarity is used at High level.
+
+The TIM1 waveform can be displayed using an oscilloscope.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+- Connect the TIM1 pins to an oscilloscope to monitor the different waveforms:
+ - TIM1_CH1 pin (PA.08)
+ - TIM1_CH1N pin (PB.13)
+ - TIM1_CH2 pin (PA.09)
+ - TIM1_CH2N pin (PB.14)
+ - TIM1_CH3 pin (PA.10)
+ - TIM1_CH3N pin (PB.15)
+
+- Connect the TIM1 break pin TIM1_BKIN pin (PB.12) to the GND. To generate a break
+ event, switch this pin level from 0V to 3.3V.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_tim.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/ComplementarySignals/stm32f10x_conf.h b/src/stm32lib/examples/TIM/ComplementarySignals/stm32f10x_conf.h new file mode 100755 index 0000000..d277318 --- /dev/null +++ b/src/stm32lib/examples/TIM/ComplementarySignals/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/ComplementarySignals/stm32f10x_it.c b/src/stm32lib/examples/TIM/ComplementarySignals/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/TIM/ComplementarySignals/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/ComplementarySignals/stm32f10x_it.h b/src/stm32lib/examples/TIM/ComplementarySignals/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/ComplementarySignals/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/DMA/main.c b/src/stm32lib/examples/TIM/DMA/main.c new file mode 100755 index 0000000..989f9e6 --- /dev/null +++ b/src/stm32lib/examples/TIM/DMA/main.c @@ -0,0 +1,260 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define TIM1_CCR3_Address 0x40012C3C
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+u16 SRC_Buffer[3] = {3071, 1791, 511};
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void DMA_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* GPIO Configuration */
+ GPIO_Configuration();
+
+ /* DMA Configuration */
+ DMA_Configuration();
+
+ /* TIM1 DMA Transfer example -------------------------------------------------
+ TIM1CLK = 72 MHz, Prescaler = 0, TIM1 counter clock = 72 MHz
+ The TIM1 Channel3 is configured to generate a complementary PWM signal with
+ a frequency equal to: TIM1 counter clock / (TIM1_Period + 1) = 17.57 KHz and
+ a variable duty cycle that is changed by the DMA after a specific number of
+ Update DMA request.
+ The number of this repetitive requests is defined by the TIM1 Repetion counter,
+ each 3 Update Requests, the TIM1 Channel 3 Duty Cycle changes to the next new
+ value defined by the SRC_Buffer .
+ ----------------------------------------------------------------------------- */
+
+ /* TIM1 Peripheral Configuration ----------------------------------------*/
+ /* Time Base configuration */
+ TIM_TimeBaseStructure.TIM_Prescaler = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseStructure.TIM_Period = 4095;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_RepetitionCounter = 2;
+
+ TIM_TimeBaseInit(TIM1, &TIM_TimeBaseStructure);
+
+ /* Channel 3 Configuration in PWM mode */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = 127;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low;
+ TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_Low;
+ TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
+ TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCIdleState_Reset;
+
+ TIM_OC3Init(TIM1, &TIM_OCInitStructure);
+
+ /* TIM1 Update DMA Request enable */
+ TIM_DMACmd(TIM1, TIM_DMA_Update, ENABLE);
+
+ /* TIM1 counter enable */
+ TIM_Cmd(TIM1, ENABLE);
+
+ /* Main Output Enable */
+ TIM_CtrlPWMOutputs(TIM1, ENABLE);
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/4 */
+ RCC_PCLK1Config(RCC_HCLK_Div4);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* TIM1, GPIOA and GPIOB clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA |
+ RCC_APB2Periph_GPIOB, ENABLE);
+ /* DMA clock enable */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the TIM1 Pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* GPIOA Configuration: Channel 3 as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* GPIOB Configuration: Channel 3N as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_15;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : DMA_Configuration
+* Description : Configures the DMA.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_Configuration(void)
+{
+ DMA_InitTypeDef DMA_InitStructure;
+
+ /* DMA1 Channel5 Config */
+ DMA_DeInit(DMA1_Channel5);
+
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (u32)TIM1_CCR3_Address;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)SRC_Buffer;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
+ DMA_InitStructure.DMA_BufferSize = 3;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+
+ DMA_Init(DMA1_Channel5, &DMA_InitStructure);
+
+ /* DMA1 Channel5 enable */
+ DMA_Cmd(DMA1_Channel5, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/DMA/readme.txt b/src/stm32lib/examples/TIM/DMA/readme.txt new file mode 100755 index 0000000..8d0eb63 --- /dev/null +++ b/src/stm32lib/examples/TIM/DMA/readme.txt @@ -0,0 +1,70 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM DMA example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to use DMA with TIM1 Update request
+to transfer Data from memory to TIM1 Capture Compare Register3.
+
+TIM1CLK = 72 MHz, Prescaler = 0, TIM1 counter clock = 72 MHz
+The TIM1 Channel3 is configured to generate a complementary PWM signal with
+a frequency equal to: TIM1 counter clock / (TIM1_Period + 1) = 17.57 KHz
+
+The TIM1 Channel3 is configured to generate a complementary PWM signal with
+a frequency equal to 17.578 KHz and a variable duty cycle that is changed
+by the DMA after a specific number of Update event.
+The number of this repetitive requests is defined by the TIM1 Repetion counter,
+each 3 Update Requests, the TIM1 Channel3 Duty Cycle changes to the next new value
+defined by the SRC_Buffer.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+Connect the pins
+ - TIM1 CH3 (PA.10)
+ - TIM1 CH3N (PB.15)
+to an oscilloscope to monitor the different waveforms.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32F10x_lib.c
+ + stm32F10x_tim.c
+ + stm32F10x_gpio.c
+ + stm32F10x_rcc.c
+ + stm32F10x_dma.c
+ + stm32F10x_nvic.c
+ + stm32F10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/DMA/stm32f10x_conf.h b/src/stm32lib/examples/TIM/DMA/stm32f10x_conf.h new file mode 100755 index 0000000..04ca366 --- /dev/null +++ b/src/stm32lib/examples/TIM/DMA/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/DMA/stm32f10x_it.c b/src/stm32lib/examples/TIM/DMA/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/TIM/DMA/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/DMA/stm32f10x_it.h b/src/stm32lib/examples/TIM/DMA/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/DMA/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/ExtTrigger_Synchro/main.c b/src/stm32lib/examples/TIM/ExtTrigger_Synchro/main.c new file mode 100755 index 0000000..0ad57eb --- /dev/null +++ b/src/stm32lib/examples/TIM/ExtTrigger_Synchro/main.c @@ -0,0 +1,291 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_ICInitTypeDef TIM_ICInitStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+void GPIO_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+ /* Timers synchronisation in cascade mode with an external trigger -----
+ 1/TIM2 is configured as Master Timer:
+ - Toggle Mode is used
+ - The TIM2 Enable event is used as Trigger Output
+
+ 2/TIM2 is configured as Slave Timer for an external Trigger connected
+ to TIM2 TI2 pin (TIM2 CH2 configured as input pin):
+ - The TIM2 TI2FP2 is used as Trigger Input
+ - Rising edge is used to start and stop the TIM2: Gated Mode.
+
+ 3/TIM3 is slave for TIM2 and Master for TIM4,
+ - Toggle Mode is used
+ - The ITR1(TIM2) is used as input trigger
+ - Gated mode is used, so start and stop of slave counter
+ are controlled by the Master trigger output signal(TIM2 enable event).
+ - The TIM3 enable event is used as Trigger Output.
+
+ 4/TIM4 is slave for TIM3,
+ - Toggle Mode is used
+ - The ITR2(TIM3) is used as input trigger
+ - Gated mode is used, so start and stop of slave counter
+ are controlled by the Master trigger output signal(TIM3 enable event).
+
+ The TIMxCLK is fixed to 72 MHZ, the Prescaler is equal to 2 so the TIMx clock counter
+ is equal to 24 MHz.
+ The Three Timers are running at:
+ TIMx frequency = TIMx clock counter/ 2*(TIMx_Period + 1) = 162.1 KHz.
+
+ The starts and stops of the TIM2 counters are controlled by the
+ external trigger.
+ The TIM3 starts and stops are controlled by the TIM2, and the TIM4
+ starts and stops are controlled by the TIM3.
+ -------------------------------------------------------------------- */
+
+ /* Time base configuration */
+ TIM_TimeBaseStructure.TIM_Period = 73;
+ TIM_TimeBaseStructure.TIM_Prescaler = 2;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+
+ TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
+
+ TIM_TimeBaseStructure.TIM_Period = 73;
+ TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
+
+ TIM_TimeBaseStructure.TIM_Period = 73;
+ TIM_TimeBaseInit(TIM4, &TIM_TimeBaseStructure);
+
+ /* Master Configuration in Toggle Mode */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Toggle;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = 64;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
+
+ TIM_OC1Init(TIM2, &TIM_OCInitStructure);
+
+ /* TIM2 Input Capture Configuration */
+ TIM_ICInitStructure.TIM_Channel = TIM_Channel_2;
+ TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
+ TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
+ TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
+ TIM_ICInitStructure.TIM_ICFilter = 0;
+
+ TIM_ICInit(TIM2, &TIM_ICInitStructure);
+
+ /* TIM2 Input trigger configuration: External Trigger connected to TI2 */
+ TIM_SelectInputTrigger(TIM2, TIM_TS_TI2FP2);
+ TIM_SelectSlaveMode(TIM2, TIM_SlaveMode_Gated);
+
+ /* Select the Master Slave Mode */
+ TIM_SelectMasterSlaveMode(TIM2, TIM_MasterSlaveMode_Enable);
+
+ /* Master Mode selection: TIM2 */
+ TIM_SelectOutputTrigger(TIM2, TIM_TRGOSource_Enable);
+
+ /* Slaves Configuration: Toggle Mode */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Toggle;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+
+ TIM_OC1Init(TIM3, &TIM_OCInitStructure);
+
+ TIM_OC1Init(TIM4, &TIM_OCInitStructure);
+
+ /* Slave Mode selection: TIM3 */
+ TIM_SelectInputTrigger(TIM3, TIM_TS_ITR1);
+ TIM_SelectSlaveMode(TIM3, TIM_SlaveMode_Gated);
+
+ /* Select the Master Slave Mode */
+ TIM_SelectMasterSlaveMode(TIM3, TIM_MasterSlaveMode_Enable);
+
+ /* Master Mode selection: TIM3 */
+ TIM_SelectOutputTrigger(TIM3, TIM_TRGOSource_Enable);
+
+ /* Slave Mode selection: TIM4 */
+ TIM_SelectInputTrigger(TIM4, TIM_TS_ITR2);
+ TIM_SelectSlaveMode(TIM4, TIM_SlaveMode_Gated);
+
+ /* TIM enable counter */
+ TIM_Cmd(TIM2, ENABLE);
+ TIM_Cmd(TIM3, ENABLE);
+ TIM_Cmd(TIM4, ENABLE);
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+ /* TIM2, TIM3 and TIM4 clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 |
+ RCC_APB1Periph_TIM4, ENABLE);
+
+ /* GPIOA and GPIOB clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the GPIO Pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* GPIOA Configuration: PA.00(TIM2 CH1) and PA.06(TIM3 CH1) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_6;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* GPIOB Configuration: PB.06(TIM4 CH1) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
+
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* GPIOA Configuration: PA.01(TIM2 CH2) */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/ExtTrigger_Synchro/readme.txt b/src/stm32lib/examples/TIM/ExtTrigger_Synchro/readme.txt new file mode 100755 index 0000000..78e8ace --- /dev/null +++ b/src/stm32lib/examples/TIM/ExtTrigger_Synchro/readme.txt @@ -0,0 +1,95 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM ExTrigger_Synchro example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+
+This example shows how to synchronize TIM peripherals in cascade mode with an
+external trigger.
+In this example three timers are used:
+
+1/TIM2 is configured as Master Timer:
+ - Toggle Mode is used
+ - The TIM2 Enable event is used as Trigger Output
+
+2/TIM2 is configured as Slave Timer for an external Trigger connected to TIM2 TI2 pin
+(TIM2 CH2 configured as input pin):
+ - The TIM2 TI2FP2 is used as Trigger Input
+ - Rising edge is used to enable and stop the TIM2: Gated Mode.
+
+3/TIM3 is slave for TIM2 and Master for TIM4,
+ - Toggle Mode is used
+ - The ITR1(TIM2) is used as input trigger
+ - Gated mode is used, so start and stop of slave counter are controlled by the Master
+ trigger output signal(TIM2 enable event).
+ - The TIM3 enable event is used as Trigger Output.
+
+4/TIM4 is slave for TIM3,
+ - Toggle Mode is used
+ - The ITR2(TIM3) is used as input trigger
+ - Gated mode is used, so start and stop of slave counter are controlled by the Master
+trigger output signal(TIM3 enable event).
+
+The TIMxCLK is fixed to 72 MHZ, the Prescaler is equal to 2 so the TIMx clock counter
+is equal to 24 MHz.
+The Three Timers are running at:
+TIMx frequency = TIMx clock counter/ 2*(TIMx_Period + 1) = 162.1 KHz.
+
+The starts and stops of the TIM2 counter are controlled by the external trigger.
+The TIM3 starts and stops are controlled by the TIM2, and the TIM4 starts and stops
+are controlled by the TIM3.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+- Connect an external trigger, with a frequency <= 40KHz, to the TIM2 CH2 pin (PA.01).
+ In this example the frequency is equal to 5 KHz.
+
+- Connect the:
+ - TIM2 CH1 (PA.00)
+ - TIM3 CH1 (PA.06)
+ - TIM4 CH1 (PB.06)
+ pins to an oscilloscope to monitor the different waveforms.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_tim.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32ff10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/ExtTrigger_Synchro/stm32f10x_conf.h b/src/stm32lib/examples/TIM/ExtTrigger_Synchro/stm32f10x_conf.h new file mode 100755 index 0000000..6a1768b --- /dev/null +++ b/src/stm32lib/examples/TIM/ExtTrigger_Synchro/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+#define _TIM2
+#define _TIM3
+#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/ExtTrigger_Synchro/stm32f10x_it.c b/src/stm32lib/examples/TIM/ExtTrigger_Synchro/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/TIM/ExtTrigger_Synchro/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/ExtTrigger_Synchro/stm32f10x_it.h b/src/stm32lib/examples/TIM/ExtTrigger_Synchro/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/ExtTrigger_Synchro/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OCActive/main.c b/src/stm32lib/examples/TIM/OCActive/main.c new file mode 100755 index 0000000..c2e0e1a --- /dev/null +++ b/src/stm32lib/examples/TIM/OCActive/main.c @@ -0,0 +1,245 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+u16 CCR1_Val = 1000;
+u16 CCR2_Val = 500;
+u16 CCR3_Val = 250;
+u16 CCR4_Val = 125;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+ /* ---------------------------------------------------------------
+ TIM2 Configuration: generate 4 signals with 4 different delays:
+ TIM2CLK = 36 MHz, Prescaler = 35999, TIM2 counter clock = 1 KHz
+ TIM2_CH1 delay = CCR1_Val/TIM2 counter clock = 1000 ms
+ TIM2_CH2 delay = CCR2_Val/TIM2 counter clock = 500 ms
+ TIM2_CH3 delay = CCR3_Val/TIM2 counter clock = 250 ms
+ TIM2_CH4 delay = CCR4_Val/TIM2 counter clock = 125 ms
+ --------------------------------------------------------------- */
+
+ /* Time base configuration */
+ TIM_TimeBaseStructure.TIM_Period = 65535;
+ TIM_TimeBaseStructure.TIM_Prescaler = 35999;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+
+ TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
+
+ /* Output Compare Active Mode configuration: Channel1 */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Active;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR1_Val;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
+ TIM_OC1Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC1PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* Output Compare Active Mode configuration: Channel2 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR2_Val;
+
+ TIM_OC2Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC2PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* Output Compare Active Mode configuration: Channel3 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR3_Val;
+
+ TIM_OC3Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC3PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* Output Compare Active Mode configuration: Channel4 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR4_Val;
+
+ TIM_OC4Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC4PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ TIM_ARRPreloadConfig(TIM2, ENABLE);
+
+ /* Set PC.06 pin */
+ GPIO_SetBits(GPIOC, GPIO_Pin_6);
+
+ /* TIM2 enable counter */
+ TIM_Cmd(TIM2, ENABLE);
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/4 */
+ RCC_PCLK1Config(RCC_HCLK_Div4);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* TIM2 clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
+
+ /* GPIOA and GPIOC clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOC, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the TIM2 and the GPIOE Pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* GPIOA Configuration:TIM2 Channel1, 2, 3 and 4 as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* GPIOC Configuration: Pin6 an Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OCActive/readme.txt b/src/stm32lib/examples/TIM/OCActive/readme.txt new file mode 100755 index 0000000..4298faf --- /dev/null +++ b/src/stm32lib/examples/TIM/OCActive/readme.txt @@ -0,0 +1,83 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM OCActive example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to configure the TIM peripheral to generate four different
+signals with four different delays.
+
+The TIMxCLK frequency is set to 36 MHz, the Prescaler is set to 35999 and used in
+Output Compare Active Mode.
+
+TIM2 counter clock = TIMxCLK / (Prescaler +1) = 1 KHz
+
+The TIM2 CCR1 register value is equal to 1000:
+TIM2_CH1 delay = CCR1_Val/TIM2 counter clock = 1000 ms
+so the TIM2 Channel 1 generates a signal with a delay equal to 1000 ms.
+
+The TIM2 CCR2 register value is equal to 500:
+TIM2_CH2 delay = CCR2_Val/TIM2 counter clock = 500 ms
+so the TIM2 Channel 2 generates a signal with a delay equal to 500 ms.
+
+The TIM2 CCR3 register value is equal to 250:
+TIM2_CH3 delay = CCR3_Val/TIM2 counter clock = 250 ms
+so the TIM2 Channel 3 generates a signal with a delay equal to 250 ms.
+
+The TIM2 CCR4 register value is equal to 125:
+TIM2_CH4 delay = CCR4_Val/TIM2 counter clock = 125 ms
+so the TIM2 Channel 4 generates a signal with a delay equal to 125 ms.
+
+The delay correspond to the time difference between PC.06 and TIM2_CHx signal rising edges
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+Connect the:
+- PC.06
+- PA.00 (TIM2_CH1)
+- PA.01 (TIM2_CH2)
+- PA.02 (TIM2_CH3)
+- PA.03 (TIM2_CH4)
+pins to an oscilloscope to monitor the different waveforms.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_tim.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/OCActive/stm32f10x_conf.h b/src/stm32lib/examples/TIM/OCActive/stm32f10x_conf.h new file mode 100755 index 0000000..05a8ba9 --- /dev/null +++ b/src/stm32lib/examples/TIM/OCActive/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OCActive/stm32f10x_it.c b/src/stm32lib/examples/TIM/OCActive/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/TIM/OCActive/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OCActive/stm32f10x_it.h b/src/stm32lib/examples/TIM/OCActive/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/OCActive/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OCInactive/main.c b/src/stm32lib/examples/TIM/OCInactive/main.c new file mode 100755 index 0000000..df759ab --- /dev/null +++ b/src/stm32lib/examples/TIM/OCInactive/main.c @@ -0,0 +1,254 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+u16 CCR1_Val = 1000;
+u16 CCR2_Val = 500;
+u16 CCR3_Val = 250;
+u16 CCR4_Val = 125;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* GPIO Configuration */
+ GPIO_Configuration();
+
+ /* ---------------------------------------------------------------
+ TIM2 Configuration: Output Compare Inactive Mode:
+ TIM2CLK = 36 MHz, Prescaler = 35999, TIM2 counter clock = 1 KHz
+ TIM2_CH1 delay = CCR1_Val/TIM2 counter clock = 1000 ms
+ TIM2_CH2 delay = CCR2_Val/TIM2 counter clock = 500 ms
+ TIM2_CH3 delay = CCR3_Val/TIM2 counter clock = 250 ms
+ TIM2_CH4 delay = CCR4_Val/TIM2 counter clock = 125 ms
+ --------------------------------------------------------------- */
+
+
+ /* Time base configuration */
+ TIM_TimeBaseStructure.TIM_Period = 65535;
+ TIM_TimeBaseStructure.TIM_Prescaler = 35999;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+
+ TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
+
+ /* Output Compare Active Mode configuration: Channel1 */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Inactive;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR1_Val;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
+
+ TIM_OC1Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC1PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* Output Compare Active Mode configuration: Channel2 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR2_Val;
+
+ TIM_OC2Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC2PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* Output Compare Active Mode configuration: Channel3 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR3_Val;
+
+ TIM_OC3Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC3PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* Output Compare Active Mode configuration: Channel4 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR4_Val;
+
+ TIM_OC4Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC4PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ TIM_ARRPreloadConfig(TIM2, ENABLE);
+
+ /* TIM IT enable */
+ TIM_ITConfig(TIM2, TIM_IT_CC1 | TIM_IT_CC2 | TIM_IT_CC3 | TIM_IT_CC4, ENABLE);
+
+ /* Set PC.06, PC.07, PC.08 and PC.09 pins */
+ GPIO_SetBits(GPIOC, GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9);
+
+ /* TIM2 enable counter */
+ TIM_Cmd(TIM2, ENABLE);
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/4 */
+ RCC_PCLK1Config(RCC_HCLK_Div4);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* TIM2 clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
+
+ /* GPIOC clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the GPIOD Pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* GPIOC Configuration: Pin6, 7, 8 and 9 as output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Enable the TIM2 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+
+ NVIC_Init(&NVIC_InitStructure);
+
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OCInactive/readme.txt b/src/stm32lib/examples/TIM/OCInactive/readme.txt new file mode 100755 index 0000000..e89d6fa --- /dev/null +++ b/src/stm32lib/examples/TIM/OCInactive/readme.txt @@ -0,0 +1,87 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM OCInactive example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+
+This example shows how to configure the TIM peripheral in Output Compare Inactive
+mode with the corresponding Interrupt requests for each channel.
+
+The TIMxCLK frequency is set to 36 MHz, the Prescaler is set to 35999 and used in
+Output Compare Inactive Mode.
+TIM2 counter clock = TIMxCLK / (Prescaler +1) = 1 KHz
+
+The TIM2 CCR1 register value is equal to 1000:
+TIM2_CC1 delay = CCR1_Val/TIM2 counter clock = 1000 ms
+so the PC.06 is reset after a delay equal to 1000 ms.
+
+The TIM2 CCR2 register value is equal to 500:
+TIM2_CC2 delay = CCR2_Val/TIM2 counter clock = 500 ms
+so the PC.07 is reset after a delay equal to 500 ms.
+
+The TIM2 CCR3 register value is equal to 250:
+TIM2_CC3 delay = CCR3_Val/TIM2 counter clock = 250 ms
+so the PC.08 is reset after a delay equal to 250 ms.
+
+The TIM2 CCR4 register value is equal to 125:
+TIM2_CC4 delay = CCR4_Val/TIM2 counter clock = 125 ms
+so the PC.09 is reset after a delay equal to 125 ms.
+
+While the counter is lower than the Output compare registers values, which
+determines the Output delay, the PC.06, PC.07, PC.08 and PC.09 pin are turned on.
+
+When the counter value reaches the Output compare registers values, the Output
+Compare interrupts are generated and, in the handler routine, these pins are turned off.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+Connect the:
+- PC.06
+- PC.07
+- PC.08
+- PC.09
+pins to an oscilloscope to monitor the different waveforms.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_tim.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into either RAM or Flash
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/OCInactive/stm32f10x_conf.h b/src/stm32lib/examples/TIM/OCInactive/stm32f10x_conf.h new file mode 100755 index 0000000..4284069 --- /dev/null +++ b/src/stm32lib/examples/TIM/OCInactive/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/* #define DEBUG 1 */
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OCInactive/stm32f10x_it.c b/src/stm32lib/examples/TIM/OCInactive/stm32f10x_it.c new file mode 100755 index 0000000..d56ce12 --- /dev/null +++ b/src/stm32lib/examples/TIM/OCInactive/stm32f10x_it.c @@ -0,0 +1,774 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+ if (TIM_GetITStatus(TIM2, TIM_IT_CC1) != RESET)
+ {
+ /* Clear TIM2 Capture Compare1 interrupt pending bit*/
+ TIM_ClearITPendingBit(TIM2, TIM_IT_CC1);
+
+ /* PC.06 turn-off after 1000 ms */
+ GPIO_ResetBits(GPIOC, GPIO_Pin_6);
+ }
+ else if (TIM_GetITStatus(TIM2, TIM_IT_CC2) != RESET)
+ {
+ /* Clear TIM2 Capture Compare2 interrupt pending bit*/
+ TIM_ClearITPendingBit(TIM2, TIM_IT_CC2);
+
+ /* PC.07 turn-off after 500 ms */
+ GPIO_ResetBits(GPIOC, GPIO_Pin_7);
+ }
+ else if (TIM_GetITStatus(TIM2, TIM_IT_CC3) != RESET)
+ {
+ /* Clear TIM2 Capture Compare3 interrupt pending bit*/
+ TIM_ClearITPendingBit(TIM2, TIM_IT_CC3);
+
+ /* PC.08 turn-off after 250 ms */
+ GPIO_ResetBits(GPIOC, GPIO_Pin_8);
+ }
+ else
+ {
+ /* Clear TIM2 Capture Compare4 interrupt pending bit*/
+ TIM_ClearITPendingBit(TIM2, TIM_IT_CC4);
+
+ /* PC.09 turn-off after 125 ms */
+ GPIO_ResetBits(GPIOC, GPIO_Pin_9);
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OCInactive/stm32f10x_it.h b/src/stm32lib/examples/TIM/OCInactive/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/OCInactive/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OCToggle/main.c b/src/stm32lib/examples/TIM/OCToggle/main.c new file mode 100755 index 0000000..408e9ee --- /dev/null +++ b/src/stm32lib/examples/TIM/OCToggle/main.c @@ -0,0 +1,245 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+vu16 CCR1_Val = 32768;
+vu16 CCR2_Val = 16384;
+vu16 CCR3_Val = 8192;
+vu16 CCR4_Val = 4096;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* GPIO Configuration */
+ GPIO_Configuration();
+
+ /* ---------------------------------------------------------------
+ TIM2 Configuration: Output Compare Toggle Mode:
+ TIM2CLK = 36 MHz, Prescaler = 0x2, TIM2 counter clock = 12 MHz
+ CC1 update rate = TIM2 counter clock / CCR1_Val = 366.2 Hz
+ CC2 update rate = TIM2 counter clock / CCR2_Val = 732.4 Hz
+ CC3 update rate = TIM2 counter clock / CCR3_Val = 1464.8 Hz
+ CC4 update rate = TIM2 counter clock / CCR4_Val = 2929.6 Hz
+ --------------------------------------------------------------- */
+
+ /* Time base configuration */
+ TIM_TimeBaseStructure.TIM_Period = 65535;
+ TIM_TimeBaseStructure.TIM_Prescaler = 2;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+
+ TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
+
+ /* Output Compare Toggle Mode configuration: Channel1 */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Toggle;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR1_Val;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low;
+ TIM_OC1Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC1PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* Output Compare Toggle Mode configuration: Channel2 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR2_Val;
+
+ TIM_OC2Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC2PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* Output Compare Toggle Mode configuration: Channel3 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR3_Val;
+
+ TIM_OC3Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC3PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* Output Compare Toggle Mode configuration: Channel4 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR4_Val;
+
+ TIM_OC4Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC4PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* TIM enable counter */
+ TIM_Cmd(TIM2, ENABLE);
+
+ /* TIM IT enable */
+ TIM_ITConfig(TIM2, TIM_IT_CC1 | TIM_IT_CC2 | TIM_IT_CC3 | TIM_IT_CC4, ENABLE);
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/4 */
+ RCC_PCLK1Config(RCC_HCLK_Div4);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* TIM2 clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
+
+ /* GPIOA clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the TIM2 Pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* GPIOA Configuration:TIM2 Channel1, 2, 3 and 4 as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Enable the TIM2 global Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OCToggle/readme.txt b/src/stm32lib/examples/TIM/OCToggle/readme.txt new file mode 100755 index 0000000..4ee2878 --- /dev/null +++ b/src/stm32lib/examples/TIM/OCToggle/readme.txt @@ -0,0 +1,82 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM OCToggle example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to configure the TIM2 peripheral to generate four different
+signals with four different frequencies.
+
+The TIM2CLK frequency is set to 36 MHz, the Prescaler is set to 2, and used in
+Output Compare Toggle Mode.
+
+TIM2 counter clock = TIMxCLK / (Prescaler +1) = 12 MHz
+
+The TIM2 CCR1 register value is equal to 32768:
+CC1 update rate = TIM2 counter clock / CCR1_Val = 366.2 Hz,
+so the TIM2 Channel 1 generates a periodic signal with a frequency equal to 183.1 Hz.
+
+The TIM2 CCR2 register is equal to 16384:
+CC2 update rate = TIM2 counter clock / CCR2_Val = 732.4 Hz
+so the TIM2 channel 2 generates a periodic signal with a frequency equal to 366.3 Hz.
+
+The TIM2 CCR3 register is equal to 8192:
+CC3 update rate = TIM2 counter clock / CCR3_Val = 1464.8 Hz
+so the TIM2 channel 3 generates a periodic signal with a frequency equal to 732.4 Hz.
+
+The TIM2 CCR4 register is equal to 4096:
+CC4 update rate = TIM2 counter clock / CCR4_Val = 2929.6 Hz
+so the TIM2 channel 4 generates a periodic signal with a frequency equal to 1464.8 Hz.
+
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+Connect the:
+- PA.00 (TIM2_CH1)
+- PA.01 (TIM2_CH2)
+- PA.02 (TIM2_CH3)
+- PA.03 (TIM2_CH4)
+pins to an oscilloscope to monitor the different waveform.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_tim.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/OCToggle/stm32f10x_conf.h b/src/stm32lib/examples/TIM/OCToggle/stm32f10x_conf.h new file mode 100755 index 0000000..1bc00d7 --- /dev/null +++ b/src/stm32lib/examples/TIM/OCToggle/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OCToggle/stm32f10x_it.c b/src/stm32lib/examples/TIM/OCToggle/stm32f10x_it.c new file mode 100755 index 0000000..bf1dba9 --- /dev/null +++ b/src/stm32lib/examples/TIM/OCToggle/stm32f10x_it.c @@ -0,0 +1,779 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+u16 capture = 0;
+extern vu16 CCR1_Val;
+extern vu16 CCR2_Val;
+extern vu16 CCR3_Val;
+extern vu16 CCR4_Val;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+ /* TIM2_CH1 toggling with frequency = 183.1 Hz */
+ if (TIM_GetITStatus(TIM2, TIM_IT_CC1) != RESET)
+ {
+ TIM_ClearITPendingBit(TIM2, TIM_IT_CC1 );
+ capture = TIM_GetCapture1(TIM2);
+ TIM_SetCompare1(TIM2, capture + CCR1_Val );
+ }
+
+ /* TIM2_CH2 toggling with frequency = 366.2 Hz */
+ if (TIM_GetITStatus(TIM2, TIM_IT_CC2) != RESET)
+ {
+ TIM_ClearITPendingBit(TIM2, TIM_IT_CC2);
+ capture = TIM_GetCapture2(TIM2);
+ TIM_SetCompare2(TIM2, capture + CCR2_Val);
+ }
+
+ /* TIM2_CH3 toggling with frequency = 732.4 Hz */
+ if (TIM_GetITStatus(TIM2, TIM_IT_CC3) != RESET)
+ {
+ TIM_ClearITPendingBit(TIM2, TIM_IT_CC3);
+ capture = TIM_GetCapture3(TIM2);
+ TIM_SetCompare3(TIM2, capture + CCR3_Val);
+ }
+
+ /* TIM2_CH4 toggling with frequency = 1464.8 Hz */
+ if (TIM_GetITStatus(TIM2, TIM_IT_CC4) != RESET)
+ {
+ TIM_ClearITPendingBit(TIM2, TIM_IT_CC4);
+ capture = TIM_GetCapture4(TIM2);
+ TIM_SetCompare4(TIM2, capture + CCR4_Val);
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OCToggle/stm32f10x_it.h b/src/stm32lib/examples/TIM/OCToggle/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/OCToggle/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OnePulse/main.c b/src/stm32lib/examples/TIM/OnePulse/main.c new file mode 100755 index 0000000..2483846 --- /dev/null +++ b/src/stm32lib/examples/TIM/OnePulse/main.c @@ -0,0 +1,240 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_ICInitTypeDef TIM_ICInitStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+
+ /* TIM2 configuration: One Pulse mode ------------------------
+ The external signal is connected to TIM2_CH2 pin (PA.01),
+ The Rising edge is used as active edge,
+ The One Pulse signal is output on TIM2_CH1 pin (PA.00)
+ The TIM_Pulse defines the delay value
+ The (TIM_Period - TIM_Pulse) defines the One Pulse value.
+ The TIM2CLK is fixed to 72 MHz, the Prescaler is 1, so the
+ TIM2 counter clock is 36 MHz.
+ The Autoreload value is 65535 (TIM2->ARR), so the maximum
+ frequency value to trigger the TIM2 input is 500 Hz.
+ The TIM_Pulse defines the delay value, the delay value is fixed
+ to 455.08 us:
+ delay = CCR1/TIM2 counter clock = 455.08 us.
+ The (TIM_Period - TIM_Pulse) defines the One Pulse value,
+ the pulse value is fixed to 1.365ms:
+ One Pulse value = (TIM_Period - TIM_Pulse)/TIM2 counter clock = 1.365 ms.
+ ------------------------------------------------------------ */
+
+ /* Time base configuration */
+ TIM_TimeBaseStructure.TIM_Period = 65535;
+ TIM_TimeBaseStructure.TIM_Prescaler = 1;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+
+ TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
+
+ /* TIM2 PWM2 Mode configuration: Channel1 */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = 16383;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
+
+ TIM_OC1Init(TIM2, &TIM_OCInitStructure);
+
+ /* TIM2 configuration in Input Capture Mode */
+
+ TIM_ICStructInit(&TIM_ICInitStructure);
+
+ TIM_ICInitStructure.TIM_Channel = TIM_Channel_2;
+ TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
+ TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
+ TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
+ TIM_ICInitStructure.TIM_ICFilter = 0;
+
+ TIM_ICInit(TIM2, &TIM_ICInitStructure);
+
+ /* One Pulse Mode selection */
+ TIM_SelectOnePulseMode(TIM2, TIM_OPMode_Single);
+
+ /* Input Trigger selection */
+ TIM_SelectInputTrigger(TIM2, TIM_TS_TI2FP2);
+
+ /* Slave Mode selection: Trigger Mode */
+ TIM_SelectSlaveMode(TIM2, TIM_SlaveMode_Trigger);
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* TIM2 clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
+
+ /* GPIOA clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the GPIOD Pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* TIM2_CH1 pin (PA.00) configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* TIM2_CH2 pin (PA.01) configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OnePulse/readme.txt b/src/stm32lib/examples/TIM/OnePulse/readme.txt new file mode 100755 index 0000000..5f00278 --- /dev/null +++ b/src/stm32lib/examples/TIM/OnePulse/readme.txt @@ -0,0 +1,71 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM OnePulse example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+
+This example shows how to use the TIM peripheral to generate a One pulse Mode
+after a Rising edge of an external signal is received in Timer Input pin.
+
+The TIM2CLK frequency is set to 72 MHz, the Prescaler is 1 so the TIM2 counter
+clock is 36 MHz.
+The Autoreload value is 65535 (TIM2->ARR), so the maximum frequency value to trigger
+the TIM2 input is 500 Hz.
+
+The TIM2 is configured as follows:
+The One Pulse mode is used, the external signal is connected to TIM2 CH2 pin (PA.01),
+the Rising edge is used as active edge, the One Pulse signal is output
+on TIM2_CH1 (PA.00).
+
+The TIM_Pulse defines the delay value, the delay value is fixed to 455.08 us:
+delay = CCR1/TIM2 counter clock = 455.08 us.
+The (TIM_Period - TIM_Pulse) defines the One Pulse value, the pulse value is fixed to 1.365ms:
+One Pulse value = (TIM_Period - TIM_Pulse)/TIM2 counter clock = 1.365 ms.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+- Connect the external signal to the TIM2_CH2 pin (PA.01)
+- Connect the TIM2_CH1 (PA.00) pin to an oscilloscope to monitor the waveform.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_tim.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/OnePulse/stm32f10x_conf.h b/src/stm32lib/examples/TIM/OnePulse/stm32f10x_conf.h new file mode 100755 index 0000000..b49cfb5 --- /dev/null +++ b/src/stm32lib/examples/TIM/OnePulse/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OnePulse/stm32f10x_it.c b/src/stm32lib/examples/TIM/OnePulse/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/TIM/OnePulse/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/OnePulse/stm32f10x_it.h b/src/stm32lib/examples/TIM/OnePulse/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/OnePulse/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/PWM_Input/main.c b/src/stm32lib/examples/TIM/PWM_Input/main.c new file mode 100755 index 0000000..e8b7168 --- /dev/null +++ b/src/stm32lib/examples/TIM/PWM_Input/main.c @@ -0,0 +1,214 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_ICInitTypeDef TIM_ICInitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+ /* TIM2 configuration: PWM Input mode ------------------------
+ The external signal is connected to TIM2 CH2 pin (PA.01),
+ The Rising edge is used as active edge,
+ The TIM2 CCR2 is used to compute the frequency value
+ The TIM2 CCR1 is used to compute the duty cycle value
+ ------------------------------------------------------------ */
+
+ TIM_ICInitStructure.TIM_Channel = TIM_Channel_2;
+ TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
+ TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
+ TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
+ TIM_ICInitStructure.TIM_ICFilter = 0x0;
+
+ TIM_PWMIConfig(TIM2, &TIM_ICInitStructure);
+
+ /* Select the TIM2 Input Trigger: TI2FP2 */
+ TIM_SelectInputTrigger(TIM2, TIM_TS_TI2FP2);
+
+ /* Select the slave Mode: Reset Mode */
+ TIM_SelectSlaveMode(TIM2, TIM_SlaveMode_Reset);
+
+ /* Enable the Master/Slave Mode */
+ TIM_SelectMasterSlaveMode(TIM2, TIM_MasterSlaveMode_Enable);
+
+ /* TIM enable counter */
+ TIM_Cmd(TIM2, ENABLE);
+
+ /* Enable the CC2 Interrupt Request */
+ TIM_ITConfig(TIM2, TIM_IT_CC2, ENABLE);
+
+ while (1);
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* TIM2 clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
+
+ /* GPIOA clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the GPIOD Pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* TIM2 channel 2 pin (PA.01) configuration */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Enable the TIM2 global Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/PWM_Input/readme.txt b/src/stm32lib/examples/TIM/PWM_Input/readme.txt new file mode 100755 index 0000000..c8c32fa --- /dev/null +++ b/src/stm32lib/examples/TIM/PWM_Input/readme.txt @@ -0,0 +1,67 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM PWM_Input example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+
+This example shows how to use the TIM peripheral to measure the frequency and
+duty cycle of an external signal.
+
+The TIMxCLK frequency is set to 72 MHz, the Prescaler is 0 so the TIM2 counter
+clock is 72 MHz. so the minimum frequency value to measure is 1100 Hz.
+TIM2 is configured in PWM Input Mode: the external signal is connected to
+TIM2 Channel2 used as input pin.
+To measure the frequency and the duty cycle we use the TIM2 CC2 interrupt request,
+so In the TIM2_IRQHandler routine, the frequency and the duty cycle of the external
+signal are computed.
+The "Frequency" variable contains the external signal frequency:
+Frequency = TIM2 counter clock / TIM2_CCR2 in Hz,
+The "DutyCycle" variable contains the external signal duty cycle:
+DutyCycle = (TIM2_CCR1*100)/(TIM2_CCR2) in %.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+
+Connect the external signal to measure to the TIM2 CH2 pin (PA.01).
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_tim.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/PWM_Input/stm32f10x_conf.h b/src/stm32lib/examples/TIM/PWM_Input/stm32f10x_conf.h new file mode 100755 index 0000000..6a1768b --- /dev/null +++ b/src/stm32lib/examples/TIM/PWM_Input/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+#define _TIM2
+#define _TIM3
+#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/PWM_Input/stm32f10x_it.c b/src/stm32lib/examples/TIM/PWM_Input/stm32f10x_it.c new file mode 100755 index 0000000..dc6fe8d --- /dev/null +++ b/src/stm32lib/examples/TIM/PWM_Input/stm32f10x_it.c @@ -0,0 +1,765 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+vu16 IC2Value = 0;
+vu16 DutyCycle = 0;
+vu32 Frequency = 0;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+ /* Clear TIM2 Capture compare interrupt pending bit */
+ TIM_ClearITPendingBit(TIM2, TIM_IT_CC2);
+
+ /* Get the Input Capture value */
+ IC2Value = TIM_GetCapture2(TIM2);
+
+ if (IC2Value != 0)
+ {
+ /* Duty cycle computation */
+ DutyCycle = (TIM_GetCapture1(TIM2) * 100) / IC2Value;
+
+ /* Frequency computation */
+ Frequency = 72000000 / IC2Value;
+ }
+ else
+ {
+ DutyCycle = 0;
+ Frequency = 0;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/PWM_Input/stm32f10x_it.h b/src/stm32lib/examples/TIM/PWM_Input/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/PWM_Input/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/PWM_Output/main.c b/src/stm32lib/examples/TIM/PWM_Output/main.c new file mode 100755 index 0000000..68be8b2 --- /dev/null +++ b/src/stm32lib/examples/TIM/PWM_Output/main.c @@ -0,0 +1,245 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+u16 CCR1_Val = 500;
+u16 CCR2_Val = 375;
+u16 CCR3_Val = 250;
+u16 CCR4_Val = 125;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* GPIO Configuration */
+ GPIO_Configuration();
+
+ /* -----------------------------------------------------------------------
+ TIM3 Configuration: generate 4 PWM signals with 4 different duty cycles:
+ TIM3CLK = 36 MHz, Prescaler = 0x0, TIM3 counter clock = 36 MHz
+ TIM3 ARR Register = 999 => TIM3 Frequency = TIM3 counter clock/(ARR + 1)
+ TIM3 Frequency = 36 KHz.
+ TIM3 Channel1 duty cycle = (TIM3_CCR1/ TIM3_ARR)* 100 = 50%
+ TIM3 Channel2 duty cycle = (TIM3_CCR2/ TIM3_ARR)* 100 = 37.5%
+ TIM3 Channel3 duty cycle = (TIM3_CCR3/ TIM3_ARR)* 100 = 25%
+ TIM3 Channel4 duty cycle = (TIM3_CCR4/ TIM3_ARR)* 100 = 12.5%
+ ----------------------------------------------------------------------- */
+
+ /* Time base configuration */
+ TIM_TimeBaseStructure.TIM_Period = 999;
+ TIM_TimeBaseStructure.TIM_Prescaler = 0;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+
+ TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
+
+ /* PWM1 Mode configuration: Channel1 */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR1_Val;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
+
+ TIM_OC1Init(TIM3, &TIM_OCInitStructure);
+
+ TIM_OC1PreloadConfig(TIM3, TIM_OCPreload_Enable);
+
+ /* PWM1 Mode configuration: Channel2 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR2_Val;
+
+ TIM_OC2Init(TIM3, &TIM_OCInitStructure);
+
+ TIM_OC2PreloadConfig(TIM3, TIM_OCPreload_Enable);
+
+ /* PWM1 Mode configuration: Channel3 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR3_Val;
+
+ TIM_OC3Init(TIM3, &TIM_OCInitStructure);
+
+ TIM_OC3PreloadConfig(TIM3, TIM_OCPreload_Enable);
+
+ /* PWM1 Mode configuration: Channel4 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR4_Val;
+
+ TIM_OC4Init(TIM3, &TIM_OCInitStructure);
+
+ TIM_OC4PreloadConfig(TIM3, TIM_OCPreload_Enable);
+
+ TIM_ARRPreloadConfig(TIM3, ENABLE);
+
+ /* TIM3 enable counter */
+ TIM_Cmd(TIM3, ENABLE);
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/4 */
+ RCC_PCLK1Config(RCC_HCLK_Div4);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* TIM3 clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE);
+
+ /* GPIOA and GPIOB clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB, ENABLE);
+
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the TIM3 Ouput Channels.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /*GPIOA Configuration: TIM3 channel 1 and 2 as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /*GPIOB Configuration: TIM3 channel 3 and 4 as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1;
+
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/PWM_Output/readme.txt b/src/stm32lib/examples/TIM/PWM_Output/readme.txt new file mode 100755 index 0000000..595afc1 --- /dev/null +++ b/src/stm32lib/examples/TIM/PWM_Output/readme.txt @@ -0,0 +1,84 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM PWM_Output example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+
+This example shows how to configure the TIM peripheral in PWM (Pulse Width Modulation)
+mode.
+The TIMxCLK frequency is set to 36 MHz, the Prescaler is 0 so the TIM3 counter clock is
+36 MHz.
+
+The TIM3 is running at 36 KHz: TIM3 Frequency = TIM3 counter clock/(ARR + 1)
+
+
+The TIM3 CCR1 register value is equal to 500, so the TIM3 Channel 1 generates a
+PWM signal with a frequency equal to 36 KHz and a duty cycle equal to 50%:
+TIM3 Channel1 duty cycle = (TIM3_CCR1/ TIM3_ARR + 1)* 100 = 50%
+
+The TIM3 CCR2 register value is equal to 375, so the TIM3 Channel 2 generates a
+PWM signal with a frequency equal to 36 KHz and a duty cycle equal to 37.5%:
+TIM3 Channel2 duty cycle = (TIM3_CCR2/ TIM3_ARR + 1)* 100 = 37.5%
+
+The TIM3 CCR3 register value is equal to 250, so the TIM3 Channel 3 generates a
+PWM signal with a frequency equal to 36 KHz and a duty cycle equal to 25%:
+TIM3 Channel3 duty cycle = (TIM3_CCR3/ TIM3_ARR + 1)* 100 = 25%
+
+The TIM3 CCR4 register value is equal to 125, so the TIM3 Channel 4 generates a
+PWM signal with a frequency equal to 36 KHz and a duty cycle equal to 12.5%:
+TIM3 Channel4 duty cycle = (TIM3_CCR4/ TIM3_ARR + 1)* 100 = 12.5%
+
+The PWM waveform can be displayed using an oscilloscope.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+Connect the:
+- PA.06: (TIM3_CH1)
+- PA.07: (TIM3_CH2)
+- PB.00: (TIM3_CH3)
+- PB.01: (TIM3_CH4)
+pins to an oscilloscope to monitor the different waveforms.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_tim.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/PWM_Output/stm32f10x_conf.h b/src/stm32lib/examples/TIM/PWM_Output/stm32f10x_conf.h new file mode 100755 index 0000000..04d7d65 --- /dev/null +++ b/src/stm32lib/examples/TIM/PWM_Output/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+//#define _TIM2
+#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/PWM_Output/stm32f10x_it.c b/src/stm32lib/examples/TIM/PWM_Output/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/TIM/PWM_Output/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/PWM_Output/stm32f10x_it.h b/src/stm32lib/examples/TIM/PWM_Output/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/PWM_Output/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/Parallel_Synchro/main.c b/src/stm32lib/examples/TIM/Parallel_Synchro/main.c new file mode 100755 index 0000000..8ae96fa --- /dev/null +++ b/src/stm32lib/examples/TIM/Parallel_Synchro/main.c @@ -0,0 +1,254 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* GPIO Configuration */
+ GPIO_Configuration();
+
+ /* Timers synchronisation in parallel mode ----------------------------
+ 1/TIM2 is configured as Master Timer:
+ - PWM Mode is used
+ - The TIM2 Update event is used as Trigger Output
+ 2/TIM3 and TIM4 are slaves for TIM2,
+ - PWM Mode is used
+ - The ITR1(TIM2) is used as input trigger for both slaves
+ - Gated mode is used, so starts and stops of slaves counters
+ are controlled by the Master trigger output signal(update event).
+
+ The TIMxCLK is fixed to 72 MHz, the TIM2 counter clock is 72 MHz.
+ The Master Timer TIM2 is running at 281.250 KHz and the duty cycle
+ is equal to 25%
+ The TIM3 is running:
+ - At (TIM2 frequency)/ (TIM3 period + 1) = 28.125 KHz and a duty cycle
+ equal to TIM3_CCR1/(TIM3_ARR + 1) = 30%
+ The TIM4 is running:
+ - At (TIM2 frequency)/ (TIM4 period + 1) = 56.250 KHz and a duty cycle
+ equal to TIM4_CCR1/(TIM4_ARR + 1) = 60%
+ -------------------------------------------------------------------- */
+
+ /* Time base configuration */
+ TIM_TimeBaseStructure.TIM_Period = 255;
+ TIM_TimeBaseStructure.TIM_Prescaler = 0;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+
+ TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
+
+ TIM_TimeBaseStructure.TIM_Period = 9;
+ TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
+
+ TIM_TimeBaseStructure.TIM_Period = 4;
+ TIM_TimeBaseInit(TIM4, &TIM_TimeBaseStructure);
+
+ /* Master Configuration in PWM1 Mode */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = 64;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
+
+ TIM_OC1Init(TIM2, &TIM_OCInitStructure);
+
+ /* Select the Master Slave Mode */
+ TIM_SelectMasterSlaveMode(TIM2, TIM_MasterSlaveMode_Enable);
+
+ /* Master Mode selection */
+ TIM_SelectOutputTrigger(TIM2, TIM_TRGOSource_Update);
+
+ /* Slaves Configuration: PWM1 Mode */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = 3;
+
+ TIM_OC1Init(TIM3, &TIM_OCInitStructure);
+
+ TIM_OC1Init(TIM4, &TIM_OCInitStructure);
+
+ /* Slave Mode selection: TIM3 */
+ TIM_SelectSlaveMode(TIM3, TIM_SlaveMode_Gated);
+ TIM_SelectInputTrigger(TIM3, TIM_TS_ITR1);
+
+ /* Slave Mode selection: TIM4 */
+ TIM_SelectSlaveMode(TIM4, TIM_SlaveMode_Gated);
+ TIM_SelectInputTrigger(TIM4, TIM_TS_ITR1);
+
+ /* TIM enable counter */
+ TIM_Cmd(TIM3, ENABLE);
+ TIM_Cmd(TIM2, ENABLE);
+ TIM_Cmd(TIM4, ENABLE);
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+ /* TIM2, TIM3 and TIM4 clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 |
+ RCC_APB1Periph_TIM4, ENABLE);
+
+
+ /* GPIOA and GPIOB clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the GPIOD Pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* GPIOA Configuration: PA0(TIM2 CH1) and PA6(TIM3 CH1) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_6;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* GPIOB Configuration: PB6(TIM4 CH1) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
+
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/Parallel_Synchro/readme.txt b/src/stm32lib/examples/TIM/Parallel_Synchro/readme.txt new file mode 100755 index 0000000..8817873 --- /dev/null +++ b/src/stm32lib/examples/TIM/Parallel_Synchro/readme.txt @@ -0,0 +1,85 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM Parallel_Synchro example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+
+This example shows how to synchronize TIM peripherals in parallel mode.
+In this example three timers are used:
+
+Timers synchronisation in parallel mode:
+
+1/TIM2 is configured as Master Timer:
+ - PWM Mode is used
+ - The TIM2 Update event is used as Trigger Output
+
+2/TIM3 and TIM4 are slaves for TIM2,
+ - PWM Mode is used
+ - The ITR1(TIM2) is used as input trigger for both slaves
+ - Gated mode is used, so starts and stops of slaves counters are controlled
+ by the Master trigger output signal(update event).
+
+The TIMxCLK is fixed to 72 MHz, the TIM2 counter clock is 72 MHz.
+The Master Timer TIM2 is running at TIM2 frequency:
+TIM2 frequency = TIM2 counter clock/ (TIM2 period + 1) = 281.250 KHz
+and the duty cycle is equal to TIM2_CCR1/(TIM2_ARR + 1) = 25%.
+
+The TIM3 is running:
+ - At (TIM2 frequency)/ (TIM3 period + 1) = 28.1250 KHz and a duty cycle equal to
+TIM3_CCR1/(TIM3_ARR + 1) = 30%
+
+The TIM4 is running:
+ - At (TIM2 frequency)/ (TIM4 period + 1) = 56.250 KHz and a duty cycle equal to
+TIM4_CCR1/(TIM4_ARR + 1) = 60%
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+Connect the
+- TIM2 CH1 (PA.00)
+- TIM3 CH1 (PA.06)
+- TIM4 CH1 (PB.06)
+pins to an oscilloscope to monitor the different waveforms.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_tim.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/Parallel_Synchro/stm32f10x_conf.h b/src/stm32lib/examples/TIM/Parallel_Synchro/stm32f10x_conf.h new file mode 100755 index 0000000..6a1768b --- /dev/null +++ b/src/stm32lib/examples/TIM/Parallel_Synchro/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+#define _TIM2
+#define _TIM3
+#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/Parallel_Synchro/stm32f10x_it.c b/src/stm32lib/examples/TIM/Parallel_Synchro/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/TIM/Parallel_Synchro/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/Parallel_Synchro/stm32f10x_it.h b/src/stm32lib/examples/TIM/Parallel_Synchro/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/Parallel_Synchro/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/TIM1_Synchro/main.c b/src/stm32lib/examples/TIM/TIM1_Synchro/main.c new file mode 100755 index 0000000..31bba97 --- /dev/null +++ b/src/stm32lib/examples/TIM/TIM1_Synchro/main.c @@ -0,0 +1,292 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+TIM_BDTRInitTypeDef TIM_BDTRInitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* GPIO Configuration */
+ GPIO_Configuration();
+
+ /* TIM1 and Timers(TIM3 and TIM4) synchronisation in parallel mode -----------
+ 1/TIM1 is configured as Master Timer:
+ - PWM Mode is used
+ - The TIM1 Update event is used as Trigger Output
+
+ 2/TIM3 and TIM4 are slaves for TIM1,
+ - PWM Mode is used
+ - The ITR0(TIM1) is used as input trigger for both slaves
+ - Gated mode is used, so starts and stops of slaves counters
+ are controlled by the Master trigger output signal(update event).
+
+ TIM1CLK = 72 MHz, Prescaler = 0, TIM1 counter clock = 72 MHz
+ The Master Timer TIM1 is running at:
+ TIM1 frequency = TIM1 counter clock / (TIM1_Period + 1) = 281.250 KHz
+ and the duty cycle is equal to:
+ TIM1_CCR1/(TIM1_ARR + 1) = 50%
+
+ The TIM3 is running:
+ - At (TIM1 frequency)/((TIM3 period + 1)* (Repetion_Counter+1)) = 18.750 KHz
+ and a duty cycle equal to TIM3_CCR1/(TIM3_ARR + 1) = 33.3%
+ The TIM4 is running:
+ - At (TIM1 frequency)/((TIM4 period + 1)* (Repetion_Counter+1)) = 28.125 KHz
+ and a duty cycle equal to TIM4_CCR1/(TIM4_ARR + 1) = 50%
+ --------------------------------------------------------------------------- */
+
+ /* TIM3 Peripheral Configuration ----------------------------------------*/
+ /* TIM3 Slave Configuration: PWM1 Mode */
+ TIM_TimeBaseStructure.TIM_Period = 2;
+ TIM_TimeBaseStructure.TIM_Prescaler = 0;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+
+ TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
+
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = 1;
+
+ TIM_OC1Init(TIM3, &TIM_OCInitStructure);
+
+ /* Slave Mode selection: TIM3 */
+ TIM_SelectSlaveMode(TIM3, TIM_SlaveMode_Gated);
+ TIM_SelectInputTrigger(TIM3, TIM_TS_ITR0);
+
+
+ /* TIM4 Peripheral Configuration ----------------------------------------*/
+ /* TIM4 Slave Configuration: PWM1 Mode */
+ TIM_TimeBaseStructure.TIM_Period = 1;
+ TIM_TimeBaseStructure.TIM_Prescaler = 0;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+
+ TIM_TimeBaseInit(TIM4, &TIM_TimeBaseStructure);
+
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = 1;
+
+ TIM_OC1Init(TIM4, &TIM_OCInitStructure);
+
+ /* Slave Mode selection: TIM4 */
+ TIM_SelectSlaveMode(TIM4, TIM_SlaveMode_Gated);
+ TIM_SelectInputTrigger(TIM4, TIM_TS_ITR0);
+
+ /* TIM1 Peripheral Configuration ----------------------------------------*/
+ /* Time Base configuration */
+ TIM_TimeBaseStructure.TIM_Prescaler = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseStructure.TIM_Period = 255;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_RepetitionCounter = 4;
+
+ TIM_TimeBaseInit(TIM1, &TIM_TimeBaseStructure);
+
+ /* Channel 1 Configuration in PWM mode */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = 127;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low;
+ TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_Low;
+ TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
+ TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCIdleState_Reset;
+
+ TIM_OC1Init(TIM1, &TIM_OCInitStructure);
+
+ /* Automatic Output enable, Break, dead time and lock configuration*/
+ TIM_BDTRInitStructure.TIM_OSSRState = TIM_OSSRState_Enable;
+ TIM_BDTRInitStructure.TIM_OSSIState = TIM_OSSIState_Enable;
+ TIM_BDTRInitStructure.TIM_LOCKLevel = TIM_LOCKLevel_1;
+ TIM_BDTRInitStructure.TIM_DeadTime = 5;
+ TIM_BDTRInitStructure.TIM_Break = TIM_Break_Disable;
+ TIM_BDTRInitStructure.TIM_BreakPolarity = TIM_BreakPolarity_High;
+ TIM_BDTRInitStructure.TIM_AutomaticOutput = TIM_AutomaticOutput_Disable;
+
+ TIM_BDTRConfig(TIM1, &TIM_BDTRInitStructure);
+
+ /* Master Mode selection */
+ TIM_SelectOutputTrigger(TIM1, TIM_TRGOSource_Update);
+
+ /* TIM1 counter enable */
+ TIM_Cmd(TIM1, ENABLE);
+
+ /* TIM enable counter */
+ TIM_Cmd(TIM3, ENABLE);
+ TIM_Cmd(TIM4, ENABLE);
+
+ /* Main Output Enable */
+ TIM_CtrlPWMOutputs(TIM1, ENABLE);
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/4 */
+ RCC_PCLK1Config(RCC_HCLK_Div4);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* TIM1, GPIOA and GPIOB clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA |
+ RCC_APB2Periph_GPIOB, ENABLE);
+
+ /* TIM3 and TIM4 clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures TIM1, TIM3 and TIM4 Pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* GPIOA Configuration: TIM1 Channel1 and TIM3 Channel1 as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_8;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* GPIOB Configuration: TIM4 Channel1 as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/TIM1_Synchro/readme.txt b/src/stm32lib/examples/TIM/TIM1_Synchro/readme.txt new file mode 100755 index 0000000..95e1f82 --- /dev/null +++ b/src/stm32lib/examples/TIM/TIM1_Synchro/readme.txt @@ -0,0 +1,84 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM TIM1_Synchro example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to synchronize TIM1 and Timers (TIM3 and TIM4) in parallel mode.
+
+Timers synchronisation in parallel mode:
+
+1/ TIM1 is configured as Master Timer:
+ - PWM Mode is used
+ - The TIM1 Update event is used as Trigger Output
+
+2/ TIM3 and TIM4 are slaves for TIM1,
+ - PWM Mode is used
+ - The ITR0(TIM1) is used as input trigger for both slaves
+ - Gated mode is used, so starts and stops of slaves counters
+ are controlled by the Master trigger output signal(update event).
+
+TIM1CLK = 72 MHz, Prescaler = 0, TIM1 counter clock = 72 MHz
+The Master Timer TIM1 is running at:
+TIM1 frequency = TIM1 counter clock / (TIM1_Period + 1) = 281.250 KHz
+and the duty cycle is equal to: TIM1_CCR1/(TIM1_ARR + 1) = 50%
+
+The TIM3 is running:
+ - At (TIM1 frequency)/ ((TIM3 period +1)* (Repetion_Counter+1)) = 18.750 KHz and
+ a duty cycle equal to TIM3_CCR1/(TIM3_ARR + 1) = 33.3%
+
+The TIM4 is running:
+ - At (TIM1 frequency)/ ((TIM4 period +1)* (Repetion_Counter+1)) = 28.125 KHz and
+ a duty cycle equal to TIM4_CCR1/(TIM4_ARR + 1) = 50%
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+Connect the:
+- TIM1 CH1 (PA.08)
+- TIM3 CH1 (PA.06)
+- TIM4 CH1 (PB.06)
+pins to an oscilloscope to monitor the different waveforms.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_tim.c
+ + stm32f10x_tim1.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/TIM1_Synchro/stm32f10x_conf.h b/src/stm32lib/examples/TIM/TIM1_Synchro/stm32f10x_conf.h new file mode 100755 index 0000000..5586058 --- /dev/null +++ b/src/stm32lib/examples/TIM/TIM1_Synchro/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+#define _TIM1
+//#define _TIM2
+#define _TIM3
+#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/TIM1_Synchro/stm32f10x_it.c b/src/stm32lib/examples/TIM/TIM1_Synchro/stm32f10x_it.c new file mode 100755 index 0000000..704430c --- /dev/null +++ b/src/stm32lib/examples/TIM/TIM1_Synchro/stm32f10x_it.c @@ -0,0 +1,741 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/TIM1_Synchro/stm32f10x_it.h b/src/stm32lib/examples/TIM/TIM1_Synchro/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/TIM1_Synchro/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/TimeBase/main.c b/src/stm32lib/examples/TIM/TimeBase/main.c new file mode 100755 index 0000000..7f2a513 --- /dev/null +++ b/src/stm32lib/examples/TIM/TimeBase/main.c @@ -0,0 +1,252 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+TIM_OCInitTypeDef TIM_OCInitStructure;
+vu16 CCR1_Val = 49152;
+vu16 CCR2_Val = 32768;
+vu16 CCR3_Val = 16384;
+vu16 CCR4_Val = 8192;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC Configuration */
+ NVIC_Configuration();
+
+ /* GPIO Configuration */
+ GPIO_Configuration();
+
+ /* ---------------------------------------------------------------
+ TIM2 Configuration: Output Compare Timing Mode:
+ TIM2CLK = 36 MHz, Prescaler = 4, TIM2 counter clock = 7.2 MHz
+ CC1 update rate = TIM2 counter clock / CCR1_Val = 146.48 Hz
+ CC2 update rate = TIM2 counter clock / CCR2_Val = 219.7 Hz
+ CC3 update rate = TIM2 counter clock / CCR3_Val = 439.4 Hz
+ CC4 update rate = TIM2 counter clock / CCR4_Val = 878.9 Hz
+ --------------------------------------------------------------- */
+
+ /* Time base configuration */
+ TIM_TimeBaseStructure.TIM_Period = 65535;
+ TIM_TimeBaseStructure.TIM_Prescaler = 0;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+
+ TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
+
+ /* Prescaler configuration */
+ TIM_PrescalerConfig(TIM2, 4, TIM_PSCReloadMode_Immediate);
+
+ /* Output Compare Timing Mode configuration: Channel1 */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Timing;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR1_Val;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
+
+ TIM_OC1Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC1PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* Output Compare Timing Mode configuration: Channel2 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR2_Val;
+
+ TIM_OC2Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC2PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* Output Compare Timing Mode configuration: Channel3 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR3_Val;
+
+ TIM_OC3Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC3PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* Output Compare Timing Mode configuration: Channel4 */
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = CCR4_Val;
+
+ TIM_OC4Init(TIM2, &TIM_OCInitStructure);
+
+ TIM_OC4PreloadConfig(TIM2, TIM_OCPreload_Disable);
+
+ /* TIM IT enable */
+ TIM_ITConfig(TIM2, TIM_IT_CC1 | TIM_IT_CC2 | TIM_IT_CC3 | TIM_IT_CC4, ENABLE);
+
+ /* TIM2 enable counter */
+ TIM_Cmd(TIM2, ENABLE);
+
+ while (1);
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/4 */
+ RCC_PCLK1Config(RCC_HCLK_Div4);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {}
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x08)
+ {}
+ }
+
+ /* TIM2 clock enable */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
+
+ /* GPIOC clock enable */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configure the GPIOD Pins.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* GPIOC Configuration:Pin6, 7, 8 and 9 as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configure the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Enable the TIM2 gloabal Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ while (1)
+ {}
+}
+#endif
+
+
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/TimeBase/readme.txt b/src/stm32lib/examples/TIM/TimeBase/readme.txt new file mode 100755 index 0000000..21a0ad2 --- /dev/null +++ b/src/stm32lib/examples/TIM/TimeBase/readme.txt @@ -0,0 +1,87 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the TIM Time Base example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+
+This example shows how to configure the TIM peripheral in Output Compare Timing
+mode with the corresponding Interrupt requests for each channel in order to generate
+4 different time bases.
+
+The TIMxCLK frequency is set to 36 MHz, the Prescaler is 4 so the TIM2 counter
+clock is 7.2 MHz.
+
+The TIM2 CC1 register value is equal to 49152,
+CC1 update rate = TIM2 counter clock / CCR1_Val = 146.48 Hz,
+so the TIM2 Channel 1 generates an interrupt each 6.8ms
+
+The TIM2 CC2 register is equal to 32768,
+CC2 update rate = TIM2 counter clock / CCR2_Val = 219.7 HzHz
+so the TIM2 Channel 2 generates an interrupt each 4.55ms
+
+The TIM2 CC3 register is equal to 16384,
+CC3 update rate = TIM2 counter clock / CCR3_Val = 439.4Hz
+so the TIM2 Channel 3 generates an interrupt each 2.27ms
+
+The TIM2 CC4 register is equal to 8192,
+CC4 update rate = TIM2 counter clock / CCR4_Val = 878.9 Hz
+so the TIM2 Channel 4 generates an interrupt each 1.13ms.
+
+
+When the counter value reaches the Output compare registers values, the Output
+Compare interrupts are generated and, in the handler routine, 4 pins(PC.06, PC.07,
+PC.08 and PC.09) are toggled with the following frequencies:
+
+- PC.06: 73.24Hz (CC1)
+- PC.07: 109.8Hz (CC2)
+- PC.08: 219.7Hz (CC3)
+- PC.09: 439.4Hz (CC4)
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Interrupt handlers header file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+Connect an oscilloscope on PC.06, PC.07, PC.08 and PC.09 to show the different
+Time Base signals.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_tim.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/TIM/TimeBase/stm32f10x_conf.h b/src/stm32lib/examples/TIM/TimeBase/stm32f10x_conf.h new file mode 100755 index 0000000..c748290 --- /dev/null +++ b/src/stm32lib/examples/TIM/TimeBase/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+#define _TIM
+//#define _TIM1
+#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/TimeBase/stm32f10x_it.c b/src/stm32lib/examples/TIM/TimeBase/stm32f10x_it.c new file mode 100755 index 0000000..92e1130 --- /dev/null +++ b/src/stm32lib/examples/TIM/TimeBase/stm32f10x_it.c @@ -0,0 +1,784 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+u16 capture = 0;
+extern vu16 CCR1_Val;
+extern vu16 CCR2_Val;
+extern vu16 CCR3_Val;
+extern vu16 CCR4_Val;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+ if (TIM_GetITStatus(TIM2, TIM_IT_CC1) != RESET)
+ {
+ TIM_ClearITPendingBit(TIM2, TIM_IT_CC1);
+
+ /* Pin PC.06 toggling with frequency = 73.24 Hz */
+ GPIO_WriteBit(GPIOC, GPIO_Pin_6, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIOC, GPIO_Pin_6)));
+ capture = TIM_GetCapture1(TIM2);
+ TIM_SetCompare1(TIM2, capture + CCR1_Val);
+ }
+ else if (TIM_GetITStatus(TIM2, TIM_IT_CC2) != RESET)
+ {
+ TIM_ClearITPendingBit(TIM2, TIM_IT_CC2);
+
+ /* Pin PC.07 toggling with frequency = 109.8 Hz */
+ GPIO_WriteBit(GPIOC, GPIO_Pin_7, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIOC, GPIO_Pin_7)));
+ capture = TIM_GetCapture2(TIM2);
+ TIM_SetCompare2(TIM2, capture + CCR2_Val);
+ }
+ else if (TIM_GetITStatus(TIM2, TIM_IT_CC3) != RESET)
+ {
+ TIM_ClearITPendingBit(TIM2, TIM_IT_CC3);
+
+ /* Pin PC.08 toggling with frequency = 219.7 Hz */
+ GPIO_WriteBit(GPIOC, GPIO_Pin_8, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIOC, GPIO_Pin_8)));
+ capture = TIM_GetCapture3(TIM2);
+ TIM_SetCompare3(TIM2, capture + CCR3_Val);
+ }
+ else
+ {
+ TIM_ClearITPendingBit(TIM2, TIM_IT_CC4);
+
+ /* Pin PC.09 toggling with frequency = 439.4 Hz */
+ GPIO_WriteBit(GPIOC, GPIO_Pin_9, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIOC, GPIO_Pin_9)));
+ capture = TIM_GetCapture4(TIM2);
+ TIM_SetCompare4(TIM2, capture + CCR4_Val);
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/TIM/TimeBase/stm32f10x_it.h b/src/stm32lib/examples/TIM/TimeBase/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/TIM/TimeBase/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/DMA_Interrupt/main.c b/src/stm32lib/examples/USART/DMA_Interrupt/main.c new file mode 100755 index 0000000..e1b031d --- /dev/null +++ b/src/stm32lib/examples/USART/DMA_Interrupt/main.c @@ -0,0 +1,362 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define USART1_DR_Base 0x40013804
+#define USART2_DR_Base 0x40004404
+#define TxBufferSize1 (countof(TxBuffer1) - 1)
+#define TxBufferSize2 (countof(TxBuffer2) - 1)
+
+/* Private macro -------------------------------------------------------------*/
+#define countof(a) (sizeof(a) / sizeof(*(a)))
+
+/* Private variables ---------------------------------------------------------*/
+USART_InitTypeDef USART_InitStructure;
+u8 TxBuffer1[] = "USART DMA Interrupt: USART1 -> USART2 using DMA Tx and Rx Flag";
+u8 TxBuffer2[] = "USART DMA Interrupt: USART2 -> USART1 using DMA Tx and Rx Interrupt";
+u8 RxBuffer1[TxBufferSize2];
+u8 RxBuffer2[TxBufferSize1];
+u8 NbrOfDataToRead = TxBufferSize1;
+u8 index = 0;
+volatile TestStatus TransferStatus1 = FAILED, TransferStatus2 = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+void DMA_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+ /* Configure the DMA */
+ DMA_Configuration();
+
+/* USART1 and USART2 configuration ------------------------------------------------------*/
+ /* USART and USART2 configured as follow:
+ - BaudRate = 230400 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+ */
+
+ USART_InitStructure.USART_BaudRate = 230400;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_No;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+
+ /* Configure USART1 */
+ USART_Init(USART1, &USART_InitStructure);
+ /* Configure USART2 */
+ USART_Init(USART2, &USART_InitStructure);
+
+ /* Enable USART1 DMA TX request */
+ USART_DMACmd(USART1, USART_DMAReq_Tx, ENABLE);
+
+ /* Enable USART2 DMA TX request */
+ USART_DMACmd(USART2, USART_DMAReq_Tx, ENABLE);
+
+ /* Enable the USART2 Receive Interrupt */
+ USART_ITConfig(USART2, USART_IT_RXNE, ENABLE);
+
+ /* Enable DMA1 Channel4 */
+ DMA_Cmd(DMA1_Channel4, ENABLE);
+ /* Enable DMA1 Channel7 */
+ DMA_Cmd(DMA1_Channel7, ENABLE);
+
+ /* Enable the USART1 */
+ USART_Cmd(USART1, ENABLE);
+ /* Enable the USART2 */
+ USART_Cmd(USART2, ENABLE);
+
+ /* Receive the TxBuffer2 */
+ while(index < TxBufferSize2)
+ {
+ while(USART_GetFlagStatus(USART1, USART_FLAG_RXNE) == RESET)
+ {
+ }
+ RxBuffer1[index++] = USART_ReceiveData(USART1);
+ }
+
+ /* Wait until DMA1_Channel 4 Transfer Complete */
+ while (DMA_GetFlagStatus(DMA1_FLAG_TC4) == RESET)
+ {
+ }
+ /* Wait until DMA1_Channel 7 Transfer Complete */
+ while (DMA_GetFlagStatus(DMA1_FLAG_TC7) == RESET)
+ {
+ }
+
+ /* Check the received data with the send ones */
+ TransferStatus1 = Buffercmp(TxBuffer2, RxBuffer1, TxBufferSize2);
+ /* TransferStatus1 = PASSED, if the data transmitted from USART2 and
+ received by USART1 are the same */
+ /* TransferStatus1 = FAILED, if the data transmitted from USART2 and
+ received by USART1 are different */
+ TransferStatus2 = Buffercmp(TxBuffer1, RxBuffer2, TxBufferSize1);
+ /* TransferStatus2 = PASSED, if the data transmitted from USART1 and
+ received by USART2 are the same */
+ /* TransferStatus2 = FAILED, if the data transmitted from USART1 and
+ received by USART2 are different */
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* DMA clock enable */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+ /* Enable USART1, GPIOA, GPIOx and AFIO clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA |
+ RCC_APB2Periph_GPIOx | RCC_APB2Periph_AFIO, ENABLE);
+ /* Enable USART2 clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+#ifdef USE_STM3210B_EVAL
+ /* Enable the USART2 Pins Software Remapping */
+ GPIO_PinRemapConfig(GPIO_Remap_USART2, ENABLE);
+#endif
+
+ /* Configure USART1 Rx (PA.10) as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART2 Rx as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_RxPin;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+
+ /* Configure USART1 Tx (PA.09) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART2 Tx as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_TxPin;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Enable the USART2 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : DMA_Configuration
+* Description : Configures the DMA.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_Configuration(void)
+{
+ DMA_InitTypeDef DMA_InitStructure;
+
+ /* DMA1 Channel4 (triggered by USART1 Tx event) Config */
+ DMA_DeInit(DMA1_Channel4);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = USART1_DR_Base;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)TxBuffer1;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
+ DMA_InitStructure.DMA_BufferSize = TxBufferSize1;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA1_Channel4, &DMA_InitStructure);
+
+ /* DMA1 Channel7 (triggered by USART2 Tx event) Config */
+ DMA_DeInit(DMA1_Channel7);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = USART2_DR_Base;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)TxBuffer2;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
+ DMA_InitStructure.DMA_BufferSize = TxBufferSize2;
+ DMA_Init(DMA1_Channel7, &DMA_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/DMA_Interrupt/platform_config.h b/src/stm32lib/examples/USART/DMA_Interrupt/platform_config.h new file mode 100755 index 0000000..14ceaf4 --- /dev/null +++ b/src/stm32lib/examples/USART/DMA_Interrupt/platform_config.h @@ -0,0 +1,48 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+#define GPIOx GPIOD
+#define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOD
+#define GPIO_TxPin GPIO_Pin_5
+#define GPIO_RxPin GPIO_Pin_6
+#elif defined USE_STM3210E_EVAL
+#define GPIOx GPIOA
+#define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOA
+#define GPIO_TxPin GPIO_Pin_2
+#define GPIO_RxPin GPIO_Pin_3
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/DMA_Interrupt/readme.txt b/src/stm32lib/examples/USART/DMA_Interrupt/readme.txt new file mode 100755 index 0000000..06af648 --- /dev/null +++ b/src/stm32lib/examples/USART/DMA_Interrupt/readme.txt @@ -0,0 +1,82 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the USART DMA Interrupt Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a basic communication between USART1 and USART2 using DMA
+capability, flags and interrupts.
+
+First, the DMA transfers data from TxBuffer2 buffer to USART2 Transmit data register,
+then this data is sent to USART1. Data received by USART1 is transferred using
+RXNE flag and stored in RxBuffer1 then compared with the sent ones and
+the result of this comparison is stored in the "TransferStatus1" variable.
+
+In the same time, the DMA transfers data from TxBuffer1 buffer to USART1 Transmit
+data register, then this data is sent to USART2. Data received by USART2 is
+transferred using Receive interrupt and stored in RxBuffer2 then compared with
+the sent ones and the result of this comparison is stored in the "TransferStatus2"
+variable.
+
+USART1 and USART2 configured as follow:
+ - BaudRate = 230400 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Connect a null-modem female/female RS232 cable between CN5 and CN6.
+ - Note: in this case USART2 Tx and Rx pins are remapped by software on
+ PD.05 and PD.06 respectively.
+
+ + STM3210E-EVAL
+ - Connect a null-modem female/female RS232 cable between CN12 and CN8.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_usart.c
+ + stm32f10x_nvic.c
+ + stm32f10x_dma.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/USART/DMA_Interrupt/stm32f10x_conf.h b/src/stm32lib/examples/USART/DMA_Interrupt/stm32f10x_conf.h new file mode 100755 index 0000000..784382d --- /dev/null +++ b/src/stm32lib/examples/USART/DMA_Interrupt/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+#define _USART1
+#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/DMA_Interrupt/stm32f10x_it.c b/src/stm32lib/examples/USART/DMA_Interrupt/stm32f10x_it.c new file mode 100755 index 0000000..0d92518 --- /dev/null +++ b/src/stm32lib/examples/USART/DMA_Interrupt/stm32f10x_it.c @@ -0,0 +1,828 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+u8 RxCounter = 0;
+extern u8 RxBuffer2[];
+extern u8 NbrOfDataToRead;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+ if(USART_GetITStatus(USART2, USART_IT_RXNE) != RESET)
+ {
+ /* Read one byte from the receive data register */
+ RxBuffer2[RxCounter++] = USART_ReceiveData(USART2);
+
+ /* Clear the USART2 Receive interrupt */
+ USART_ClearITPendingBit(USART2, USART_IT_RXNE);
+
+ if(RxCounter == NbrOfDataToRead)
+ {
+ /* Disable the USART2 Receive interrupt */
+ USART_ITConfig(USART2, USART_IT_RXNE, DISABLE);
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/DMA_Interrupt/stm32f10x_it.h b/src/stm32lib/examples/USART/DMA_Interrupt/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/USART/DMA_Interrupt/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/DMA_Polling/main.c b/src/stm32lib/examples/USART/DMA_Polling/main.c new file mode 100755 index 0000000..a080ce8 --- /dev/null +++ b/src/stm32lib/examples/USART/DMA_Polling/main.c @@ -0,0 +1,366 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum { FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define USART1_DR_Base 0x40013804
+#define USART2_DR_Base 0x40004404
+#define TxBufferSize1 (countof(TxBuffer1) - 1)
+#define TxBufferSize2 (countof(TxBuffer2) - 1)
+
+/* Private macro -------------------------------------------------------------*/
+#define countof(a) (sizeof(a) / sizeof(*(a)))
+
+/* Private variables ---------------------------------------------------------*/
+USART_InitTypeDef USART_InitStructure;
+u8 TxBuffer1[] = "USART DMA Polling: USART1 -> USART2 using DMA";
+u8 TxBuffer2[] = "USART DMA Polling: USART2 -> USART1 using DMA";
+u8 RxBuffer1[TxBufferSize2];
+u8 RxBuffer2[TxBufferSize1];
+volatile TestStatus TransferStatus1 = FAILED;
+volatile TestStatus TransferStatus2 = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+void DMA_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+ /* Configure the DMA */
+ DMA_Configuration();
+
+/* USART1 and USART2 configuration ------------------------------------------------------*/
+ /* USART1 and USART2 configured as follow:
+ - BaudRate = 230400 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+ */
+ USART_InitStructure.USART_BaudRate = 230400;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_No;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+
+ /* Configure USART1 */
+ USART_Init(USART1, &USART_InitStructure);
+ /* Configure USART2 */
+ USART_Init(USART2, &USART_InitStructure);
+
+ /* Enable USART1 DMA Rx and TX request */
+ USART_DMACmd(USART1, USART_DMAReq_Rx | USART_DMAReq_Tx, ENABLE);
+ /* Enable USART2 DMA Rx and TX request */
+ USART_DMACmd(USART2, USART_DMAReq_Rx | USART_DMAReq_Tx, ENABLE);
+
+ /* Enable DMA1 Channel4 */
+ DMA_Cmd(DMA1_Channel4, ENABLE);
+ /* Enable DMA1 Channel5 */
+ DMA_Cmd(DMA1_Channel5, ENABLE);
+ /* Enable DMA1 Channel6 */
+ DMA_Cmd(DMA1_Channel6, ENABLE);
+ /* Enable DMA1 Channel7 */
+ DMA_Cmd(DMA1_Channel7, ENABLE);
+
+ /* Enable the USART1 */
+ USART_Cmd(USART1, ENABLE);
+ /* Enable the USART2 */
+ USART_Cmd(USART2, ENABLE);
+
+ /* Wait until DMA1_Channel 4 Transfer Complete */
+ while (DMA_GetFlagStatus(DMA1_FLAG_TC4) == RESET)
+ {
+ }
+ /* Wait until DMA1_Channel 5 Transfer Complete */
+ while (DMA_GetFlagStatus(DMA1_FLAG_TC5) == RESET)
+ {
+ }
+ /* Wait until DMA1_Channel 6 Transfer Complete */
+ while (DMA_GetFlagStatus(DMA1_FLAG_TC6) == RESET)
+ {
+ }
+ /* Wait until DMA1_Channel 7 Transfer Complete */
+ while (DMA_GetFlagStatus(DMA1_FLAG_TC7) == RESET)
+ {
+ }
+ /* Check the received data with the send ones */
+ TransferStatus1 = Buffercmp(TxBuffer2, RxBuffer1, TxBufferSize2);
+ /* TransferStatus1 = PASSED, if the data transmitted from USART2 and
+ received by USART1 are the same */
+ /* TransferStatus1 = FAILED, if the data transmitted from USART2 and
+ received by USART1 are different */
+ TransferStatus2 = Buffercmp(TxBuffer1, RxBuffer2, TxBufferSize1);
+ /* TransferStatus2 = PASSED, if the data transmitted from USART1 and
+ received by USART2 are the same */
+ /* TransferStatus2 = FAILED, if the data transmitted from USART1 and
+ received by USART2 are different */
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* DMA1 clock enable */
+ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+
+ /* Enable USART1, GPIOA, GPIOx and AFIO clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA |
+ RCC_APB2Periph_GPIOx | RCC_APB2Periph_AFIO, ENABLE);
+ /* Enable USART2 clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+#ifdef USE_STM3210B_EVAL
+ /* Enable the USART2 Pins Software Remapping */
+ GPIO_PinRemapConfig(GPIO_Remap_USART2, ENABLE);
+#endif
+
+ /* Configure USART1 Rx (PA.10) as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART2 Rx as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_RxPin;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+
+ /* Configure USART1 Tx (PA.09) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART2 Tx as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_TxPin;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : DMA_Configuration
+* Description : Configures the DMA.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_Configuration(void)
+{
+ DMA_InitTypeDef DMA_InitStructure;
+
+ /* DMA1 Channel4 (triggered by USART1 Tx event) Config */
+ DMA_DeInit(DMA1_Channel4);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = USART1_DR_Base;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)TxBuffer1;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
+ DMA_InitStructure.DMA_BufferSize = TxBufferSize1;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh;
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_Init(DMA1_Channel4, &DMA_InitStructure);
+
+ /* DMA1 Channel5 (triggered by USART1 Rx event) Config */
+ DMA_DeInit(DMA1_Channel5);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = USART1_DR_Base;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)RxBuffer1;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = TxBufferSize2;
+ DMA_Init(DMA1_Channel5, &DMA_InitStructure);
+
+ /* DMA1 Channel6 (triggered by USART2 Rx event) Config */
+ DMA_DeInit(DMA1_Channel6);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = USART2_DR_Base;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)RxBuffer2;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+ DMA_InitStructure.DMA_BufferSize = TxBufferSize1;
+ DMA_Init(DMA1_Channel6, &DMA_InitStructure);
+
+ /* DMA1 Channel7 (triggered by USART2 Tx event) Config */
+ DMA_DeInit(DMA1_Channel7);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = USART2_DR_Base;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (u32)TxBuffer2;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
+ DMA_InitStructure.DMA_BufferSize = TxBufferSize2;
+ DMA_Init(DMA1_Channel7, &DMA_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/DMA_Polling/platform_config.h b/src/stm32lib/examples/USART/DMA_Polling/platform_config.h new file mode 100755 index 0000000..14ceaf4 --- /dev/null +++ b/src/stm32lib/examples/USART/DMA_Polling/platform_config.h @@ -0,0 +1,48 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+#define GPIOx GPIOD
+#define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOD
+#define GPIO_TxPin GPIO_Pin_5
+#define GPIO_RxPin GPIO_Pin_6
+#elif defined USE_STM3210E_EVAL
+#define GPIOx GPIOA
+#define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOA
+#define GPIO_TxPin GPIO_Pin_2
+#define GPIO_RxPin GPIO_Pin_3
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/DMA_Polling/readme.txt b/src/stm32lib/examples/USART/DMA_Polling/readme.txt new file mode 100755 index 0000000..8a7c316 --- /dev/null +++ b/src/stm32lib/examples/USART/DMA_Polling/readme.txt @@ -0,0 +1,81 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the USART DMA Polling Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a basic communication between USART1 and USART2 using DMA
+capability.
+
+First, the DMA transfers data from TxBuffer2 buffer to USART2 Transmit data
+register, then this data is sent to USART1. Data received by USART1 is transferred
+by DMA and stored in RxBuffer1 then compared with the send ones and the result
+of this comparison is stored in the "TransferStatus1" variable.
+
+In the same time, the DMA transfers data from TxBuffer1 buffer to USART1 Transmit
+data register, then this data is sent to USART2. Data received by USART2 is
+transferred by DMA and stored in RxBuffer2 then compared with the send ones and
+the result of this comparison is stored in the "TransferStatus2" variable.
+
+USART1 and USART2 configured as follow:
+ - BaudRate = 230400 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Connect a null-modem female/female RS232 cable between CN5 and CN6.
+ - Note: in this case USART2 Tx and Rx pins are remapped by software on
+ PD.05 and PD.06 respectively.
+
+ + STM3210E-EVAL
+ - Connect a null-modem female/female RS232 cable between CN12 and CN8.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_usart.c
+ + stm32f10x_nvic.c
+ + stm32f10x_dma.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/USART/DMA_Polling/stm32f10x_conf.h b/src/stm32lib/examples/USART/DMA_Polling/stm32f10x_conf.h new file mode 100755 index 0000000..c2b6219 --- /dev/null +++ b/src/stm32lib/examples/USART/DMA_Polling/stm32f10x_conf.h @@ -0,0 +1,169 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+/************************************* DMA ************************************/
+#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+#define _DMA1_Channel4
+#define _DMA1_Channel5
+#define _DMA1_Channel6
+#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+#define _USART1
+#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/DMA_Polling/stm32f10x_it.c b/src/stm32lib/examples/USART/DMA_Polling/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/USART/DMA_Polling/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/DMA_Polling/stm32f10x_it.h b/src/stm32lib/examples/USART/DMA_Polling/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/USART/DMA_Polling/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/HalfDuplex/main.c b/src/stm32lib/examples/USART/HalfDuplex/main.c new file mode 100755 index 0000000..d37ce13 --- /dev/null +++ b/src/stm32lib/examples/USART/HalfDuplex/main.c @@ -0,0 +1,313 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define TxBufferSize1 (countof(TxBuffer1) - 1)
+#define TxBufferSize2 (countof(TxBuffer2) - 1)
+
+/* Private macro -------------------------------------------------------------*/
+#define countof(a) (sizeof(a) / sizeof(*(a)))
+
+/* Private variables ---------------------------------------------------------*/
+USART_InitTypeDef USART_InitStructure;
+u8 TxBuffer1[] = "USART Half Duplex: USART1 -> USART2 using HalfDuplex mode";
+u8 TxBuffer2[] = "USART Half Duplex: USART2 -> USART1 using HalfDuplex mode";
+u8 RxBuffer1[TxBufferSize2];
+u8 RxBuffer2[TxBufferSize1];
+u8 NbrOfDataToRead1 = TxBufferSize2;
+u8 NbrOfDataToRead2 = TxBufferSize1;
+u8 TxCounter1 = 0, RxCounter1 = 0;
+u8 TxCounter2 = 0, RxCounter2 = 0;
+volatile TestStatus TransferStatus1 = FAILED, TransferStatus2 = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+/* USART1 and USART2 configuration ------------------------------------------------------*/
+ /* USART1 and USART2 configured as follow:
+ - BaudRate = 230400 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+
+ */
+ USART_InitStructure.USART_BaudRate = 230400;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_No;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+
+ /* Configure USART1 */
+ USART_Init(USART1, &USART_InitStructure);
+ /* Configure USART2 */
+ USART_Init(USART2, &USART_InitStructure);
+
+ /* Enable the USART1 */
+ USART_Cmd(USART1, ENABLE);
+ /* Enable the USART2 */
+ USART_Cmd(USART2, ENABLE);
+
+ /* Enable USART1 Half Duplex Mode*/
+ USART_HalfDuplexCmd(USART1, ENABLE);
+ /* Enable USART2 Half Duplex Mode*/
+ USART_HalfDuplexCmd(USART2, ENABLE);
+
+ while(NbrOfDataToRead2--)
+ {
+ /* Wait until end of transmit */
+ while(USART_GetFlagStatus(USART1, USART_FLAG_TXE) == RESET)
+ {
+ }
+ /* Write one byte in the USART1 Transmit Data Register */
+ USART_SendData(USART1, TxBuffer1[TxCounter1++]);
+
+ /* Wait the byte is entirtly received by USART2 */
+ while(USART_GetFlagStatus(USART2, USART_FLAG_RXNE) == RESET)
+ {
+ }
+ /* Store the received byte in the RxBuffer2 */
+ RxBuffer2[RxCounter2++] = USART_ReceiveData(USART2);
+ }
+
+ /* Clear the USART1 Data Register */
+ USART_ReceiveData(USART1);
+
+ while(NbrOfDataToRead1--)
+ {
+ /* Wait until end of transmit */
+ while(USART_GetFlagStatus(USART2, USART_FLAG_TXE)== RESET)
+ {
+ }
+ /* Write one byte in the USART2 Transmit Data Register */
+ USART_SendData(USART2, TxBuffer2[TxCounter2++]);
+
+ /* Wait the byte is entirtly received by USART1 */
+ while(USART_GetFlagStatus(USART1,USART_FLAG_RXNE) == RESET)
+ {
+ }
+ /* Store the received byte in the RxBuffer1 */
+ RxBuffer1[RxCounter1++] = USART_ReceiveData(USART1);
+ }
+
+ /* Check the received data with the send ones */
+ TransferStatus1 = Buffercmp(TxBuffer1, RxBuffer2, TxBufferSize1);
+ /* TransferStatus = PASSED, if the data transmitted from USART1 and
+ received by USART2 are the same */
+ /* TransferStatus = FAILED, if the data transmitted from USART1 and
+ received by USART2 are different */
+ TransferStatus2 = Buffercmp(TxBuffer2, RxBuffer1, TxBufferSize2);
+ /* TransferStatus = PASSED, if the data transmitted from USART2 and
+ received by USART1 are the same */
+ /* TransferStatus = FAILED, if the data transmitted from USART2 and
+ received by USART1 are different */
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable USART1, GPIOA, GPIOx and AFIO clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA |RCC_APB2Periph_GPIOx
+ | RCC_APB2Periph_AFIO, ENABLE);
+ /* Enable USART2 clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+#ifdef USE_STM3210B_EVAL
+ /* Enable the USART2 Pins Software Remapping */
+ GPIO_PinRemapConfig(GPIO_Remap_USART2, ENABLE);
+#endif
+
+ /* Configure USART1 Tx (PA.09) as alternate function open-drain */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART2 Tx as alternate function open-drain */
+ GPIO_InitStructure.GPIO_Pin = GPIO_TxPin;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/HalfDuplex/platform_config.h b/src/stm32lib/examples/USART/HalfDuplex/platform_config.h new file mode 100755 index 0000000..113b295 --- /dev/null +++ b/src/stm32lib/examples/USART/HalfDuplex/platform_config.h @@ -0,0 +1,46 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+#define GPIOx GPIOD
+#define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOD
+#define GPIO_TxPin GPIO_Pin_5
+#elif defined USE_STM3210E_EVAL
+#define GPIOx GPIOA
+#define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOA
+#define GPIO_TxPin GPIO_Pin_2
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/HalfDuplex/readme.txt b/src/stm32lib/examples/USART/HalfDuplex/readme.txt new file mode 100755 index 0000000..1fe24e3 --- /dev/null +++ b/src/stm32lib/examples/USART/HalfDuplex/readme.txt @@ -0,0 +1,80 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the USART Half Duplex Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a basic communication between USART1 and USART2 in
+Half-Duplex mode using flags.
+
+First, the USART1 sends data from TxBuffer1 buffer to USART2 using TXE flag.
+Data received using RXNE flag by USART2 is stored in RxBuffer2 then compared with
+the sent ones and the result of this comparison is stored in the "TransferStatus1"
+variable.
+
+Then, the USART2 sends data from TxBuffer2 buffer to USART1 using TXE flag.
+Data received using RXNE flag by USART1 is stored in RxBuffer1 then compared with
+the sent ones and the result of this comparison is stored in the "TransferStatus2"
+variable.
+
+USART1 and USART2 configured as follow:
+ - BaudRate = 230400 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - Even parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Connect USART1_Tx(PA.09) to USART2_Tx(PD.05) and connect a pull-up resistor to
+ this line (10K).
+
+ + STM3210E-EVAL
+ - Connect USART1_Tx(PA.09) to USART2_Tx(PA.02) and connect a pull-up resistor to
+ this line (10K).
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_usart.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/USART/HalfDuplex/stm32f10x_conf.h b/src/stm32lib/examples/USART/HalfDuplex/stm32f10x_conf.h new file mode 100755 index 0000000..0a79cd3 --- /dev/null +++ b/src/stm32lib/examples/USART/HalfDuplex/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+#define _USART1
+#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/HalfDuplex/stm32f10x_it.c b/src/stm32lib/examples/USART/HalfDuplex/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/USART/HalfDuplex/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/HalfDuplex/stm32f10x_it.h b/src/stm32lib/examples/USART/HalfDuplex/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/USART/HalfDuplex/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/main.c b/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/main.c new file mode 100755 index 0000000..a6939ac --- /dev/null +++ b/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/main.c @@ -0,0 +1,243 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define TxBufferSize (countof(TxBuffer) - 1)
+#define RxBufferSize 0xFF
+
+/* Private macro -------------------------------------------------------------*/
+#define countof(a) (sizeof(a) / sizeof(*(a)))
+
+/* Private variables ---------------------------------------------------------*/
+USART_InitTypeDef USART_InitStructure;
+u8 TxBuffer[] = "\n\rUSART Hyperterminal Hardware Flow Control Example: USART - \
+Hyperterminal communication using hardware flow control\n\r";
+u8 RxBuffer[RxBufferSize];
+u8 NbrOfDataToTransfer = TxBufferSize;
+u8 TxCounter = 0;
+u8 RxCounter = 0;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+
+/* USART2 configuration ------------------------------------------------------*/
+ /* USART2 configured as follow:
+ - BaudRate = 115200 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control enabled (RTS and CTS signals)
+ - Receive and transmit enabled
+ */
+ USART_InitStructure.USART_BaudRate = 115200;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_No ;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_RTS_CTS;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+
+ USART_Init(USART2, &USART_InitStructure);
+ /* Enable the USART2 */
+ USART_Cmd(USART2, ENABLE);
+
+/* Communication hyperterminal-USART2 using hardware flow control -------------*/
+ /* Send a buffer from USART to hyperterminal */
+ while(NbrOfDataToTransfer--)
+ {
+ USART_SendData(USART2, TxBuffer[TxCounter++]);
+ while(USART_GetFlagStatus(USART2, USART_FLAG_TXE) == RESET);
+ }
+
+ /* Receive a string (Max RxBufferSize bytes) from the Hyperterminal ended by '\r' (Enter key) */
+ do
+ {
+ if((USART_GetFlagStatus(USART2, USART_FLAG_RXNE) != RESET)&&(RxCounter < RxBufferSize))
+ {
+ RxBuffer[RxCounter] = USART_ReceiveData(USART2);
+ USART_SendData(USART2, RxBuffer[RxCounter++]);
+ }
+
+ }while((RxBuffer[RxCounter - 1] != '\r')&&(RxCounter != RxBufferSize));
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable GPIOx and AFIO clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOx | RCC_APB2Periph_AFIO, ENABLE);
+
+ /* Enable USART2 clocks */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+#ifdef USE_STM3210B_EVAL
+ /* Enable the USART2 Pins Software Remapping */
+ GPIO_PinRemapConfig(GPIO_Remap_USART2, ENABLE);
+#endif
+
+ /* Configure USART2 RTS and USART2 Tx as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_RTSPin | GPIO_TxPin;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+
+ /* Configure USART2 CTS and USART2 Rx as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_CTSPin | GPIO_RxPin;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/platform_config.h b/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/platform_config.h new file mode 100755 index 0000000..7ac773d --- /dev/null +++ b/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/platform_config.h @@ -0,0 +1,52 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+#define GPIOx GPIOD
+#define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOD
+#define GPIO_RTSPin GPIO_Pin_4
+#define GPIO_CTSPin GPIO_Pin_3
+#define GPIO_TxPin GPIO_Pin_5
+#define GPIO_RxPin GPIO_Pin_6
+#elif defined USE_STM3210E_EVAL
+#define GPIOx GPIOA
+#define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOA
+#define GPIO_RTSPin GPIO_Pin_1
+#define GPIO_CTSPin GPIO_Pin_0
+#define GPIO_TxPin GPIO_Pin_2
+#define GPIO_RxPin GPIO_Pin_3
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/readme.txt b/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/readme.txt new file mode 100755 index 0000000..3e1d79b --- /dev/null +++ b/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/readme.txt @@ -0,0 +1,88 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the USART Hyperterminal Hardware Flow Control
+* Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to use the USART with hardware flow
+control and communicate with the Hyperterminal.
+First, the USART2 sends the TxBuffer to the hyperterminal and still waiting for
+a string from the hyperterminal that you must enter which must end by '\r'
+character (keypad ENTER button). The communication will end if received data exceed
+255 without sending the '\r' character. Each byte received is retransmitted to the
+Hyperterminal.
+The string that you have entered is stored in the RxBuffer array. The receive
+buffer have a RxBufferSize bytes as maximum.
+
+The USART2 is configured as follow:
+ - BaudRate = 115200 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control enabled (RTS and CTS signals)
+ - Receive and transmit enabled
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Connect a null-modem female/female RS232 cable between CN5 and PC serial
+ port.
+ - Note: in this case USART2 Tx, Rx, RTS and CTS pins are remapped by software
+ on PD.05, PD.06, PD.04 and PD.03 respectively.
+
+ + STM3210E-EVAL
+ - Connect a null-modem female/female RS232 cable between CN8 and PC serial
+ port.
+ - Make sure the Jumper 4 (JP4) is in position 2<-->3.
+
+ + Hyperterminal configuration:
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - BaudRate = 115200 baud
+ - flow control: Hardware
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_usart.c
+ + stm32f10x_gpio.c
+ + stm32f10x_nvic.c
+ + stm32f10x_rcc.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/stm32f10x_conf.h b/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/stm32f10x_conf.h new file mode 100755 index 0000000..dd5d967 --- /dev/null +++ b/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+//#define _USART1
+#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/stm32f10x_it.c b/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/stm32f10x_it.h b/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/USART/HyperTerminal_HwFlowControl/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/HyperTerminal_Interrupt/main.c b/src/stm32lib/examples/USART/HyperTerminal_Interrupt/main.c new file mode 100755 index 0000000..b92d54b --- /dev/null +++ b/src/stm32lib/examples/USART/HyperTerminal_Interrupt/main.c @@ -0,0 +1,221 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+USART_InitTypeDef USART_InitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+/* USART1 configuration ------------------------------------------------------*/
+ /* USART1 configured as follow:
+ - BaudRate = 9600 baud
+ - Word Length = 8 Bits
+ - Two Stop Bit
+ - Odd parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+ */
+ USART_InitStructure.USART_BaudRate = 9600;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_2;
+ USART_InitStructure.USART_Parity = USART_Parity_Odd;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+
+ /* Configure the USART1 */
+ USART_Init(USART1, &USART_InitStructure);
+
+ /* Enable the USART Transmoit interrupt: this interrupt is generated when the
+ USART1 transmit data register is empty */
+ USART_ITConfig(USART1, USART_IT_TXE, ENABLE);
+
+ /* Enable the USART Receive interrupt: this interrupt is generated when the
+ USART1 receive data register is not empty */
+ USART_ITConfig(USART1, USART_IT_RXNE, ENABLE);
+
+ /* Enable USART1 */
+ USART_Cmd(USART1, ENABLE);
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable GPIOA and USART1 clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_USART1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure USART1 Tx (PA.09) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART1 Rx (PA.10) as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Enable the USART1 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/HyperTerminal_Interrupt/readme.txt b/src/stm32lib/examples/USART/HyperTerminal_Interrupt/readme.txt new file mode 100755 index 0000000..28cb373 --- /dev/null +++ b/src/stm32lib/examples/USART/HyperTerminal_Interrupt/readme.txt @@ -0,0 +1,82 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the USART Hyperterminal interrupt Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to use the USART1 Transmit and Receive
+interrupts to communicate with the hyperterminal.
+
+First, the USART1 sends the TxBuffer to the hyperterminal and still waiting for
+a string from the hyperterminal that you must enter.
+The string that you have entered is stored in the RxBuffer array. The receive
+buffer have a RxBufferSize bytes as maximum (the reception is stopped when this
+maximum receive value is reached).
+
+The USART1 is configured as follow:
+ - BaudRate = 9600 baud
+ - Word Length = 8 Bits (7 data bit + 1 parity bit)
+ - Two Stop Bit
+ - Odd parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+
+Note: When the parity is enabled, the computed parity is inserted at the MSB
+position of the transmitted data.
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers source file
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+ - The USART1 signals (Rx and Tx) must be connected to a DB9 connector using
+ a RS232 transceiver.
+
+ - Connect a null-modem female/female RS232 cable between the DB9 connector
+ (CN6 on STM3210B-EVAL board and CN12 on STM3210E-EVAL board) and PC serial port.
+
+ - Hyperterminal configuration:
+ - Word Length = 7 Bits
+ - Two Stop Bit
+ - Odd parity
+ - BaudRate = 9600 baud
+ - flow control: None
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_usart.c
+ + stm32f10x_gpio.c
+ + stm32f10x_nvic.c
+ + stm32f10x_rcc.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/USART/HyperTerminal_Interrupt/stm32f10x_conf.h b/src/stm32lib/examples/USART/HyperTerminal_Interrupt/stm32f10x_conf.h new file mode 100755 index 0000000..1a4c8a0 --- /dev/null +++ b/src/stm32lib/examples/USART/HyperTerminal_Interrupt/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/HyperTerminal_Interrupt/stm32f10x_it.c b/src/stm32lib/examples/USART/HyperTerminal_Interrupt/stm32f10x_it.c new file mode 100755 index 0000000..347e29a --- /dev/null +++ b/src/stm32lib/examples/USART/HyperTerminal_Interrupt/stm32f10x_it.c @@ -0,0 +1,846 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define TxBufferSize (countof(TxBuffer) - 1)
+#define RxBufferSize 0x20
+
+/* Private macro -------------------------------------------------------------*/
+#define countof(a) (sizeof(a) / sizeof(*(a)))
+
+/* Private variables ---------------------------------------------------------*/
+u8 TxBuffer[] = "\n\rUSART Hyperterminal Interrupts Example: USART-Hyperterminal\
+ communication using Interrupt\n\r";
+u8 RxBuffer[RxBufferSize];
+u8 NbrOfDataToTransfer = TxBufferSize;
+u8 NbrOfDataToRead = RxBufferSize;
+u8 TxCounter = 0;
+u16 RxCounter = 0;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+ if(USART_GetITStatus(USART1, USART_IT_RXNE) != RESET)
+ {
+ /* Read one byte from the receive data register */
+ RxBuffer[RxCounter++] = (USART_ReceiveData(USART1) & 0x7F);
+
+ if(RxCounter == NbrOfDataToRead)
+ {
+ /* Disable the USART Receive interrupt */
+ USART_ITConfig(USART1, USART_IT_RXNE, DISABLE);
+ }
+ }
+
+ if(USART_GetITStatus(USART1, USART_IT_TXE) != RESET)
+ {
+ /* Write one byte to the transmit data register */
+ USART_SendData(USART1, TxBuffer[TxCounter++]);
+
+ if(TxCounter == NbrOfDataToTransfer)
+ {
+ /* Disable the USART1 Transmit interrupt */
+ USART_ITConfig(USART1, USART_IT_TXE, DISABLE);
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/HyperTerminal_Interrupt/stm32f10x_it.h b/src/stm32lib/examples/USART/HyperTerminal_Interrupt/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/USART/HyperTerminal_Interrupt/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Interrupt/main.c b/src/stm32lib/examples/USART/Interrupt/main.c new file mode 100755 index 0000000..d92854a --- /dev/null +++ b/src/stm32lib/examples/USART/Interrupt/main.c @@ -0,0 +1,321 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum { FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define TxBufferSize1 (countof(TxBuffer1) - 1)
+#define TxBufferSize2 (countof(TxBuffer2) - 1)
+#define RxBufferSize1 TxBufferSize2
+#define RxBufferSize2 TxBufferSize1
+
+/* Private macro -------------------------------------------------------------*/
+#define countof(a) (sizeof(a) / sizeof(*(a)))
+
+/* Private variables ---------------------------------------------------------*/
+USART_InitTypeDef USART_InitStructure;
+u8 TxBuffer1[] = "USART Interrupt Example: USART1 -> USART2 using Interrupt";
+u8 TxBuffer2[] = "USART Interrupt Example: USART2 -> USART1 using Interrupt";
+u8 RxBuffer1[RxBufferSize1];
+u8 RxBuffer2[RxBufferSize2];
+vu8 TxCounter1 = 0x00;
+vu8 TxCounter2 = 0x00;
+vu8 RxCounter1 = 0x00;
+vu8 RxCounter2 = 0x00;
+u8 NbrOfDataToTransfer1 = TxBufferSize1;
+u8 NbrOfDataToTransfer2 = TxBufferSize2;
+u8 NbrOfDataToRead1 = RxBufferSize1;
+u8 NbrOfDataToRead2 = RxBufferSize2;
+volatile TestStatus TransferStatus1 = FAILED;
+volatile TestStatus TransferStatus2 = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+/* USART1 and USART2 configuration ------------------------------------------------------*/
+ /* USART and USART2 configured as follow:
+ - BaudRate = 9600 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+ */
+ USART_InitStructure.USART_BaudRate = 9600;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_No;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+
+ /* Configure USART1 */
+ USART_Init(USART1, &USART_InitStructure);
+ /* Configure USART2 */
+ USART_Init(USART2, &USART_InitStructure);
+
+ /* Enable USART1 Receive and Transmit interrupts */
+ USART_ITConfig(USART1, USART_IT_RXNE, ENABLE);
+ USART_ITConfig(USART1, USART_IT_TXE, ENABLE);
+
+ /* Enable USART2 Receive and Transmit interrupts */
+ USART_ITConfig(USART2, USART_IT_RXNE, ENABLE);
+ USART_ITConfig(USART2, USART_IT_TXE, ENABLE);
+
+ /* Enable the USART1 */
+ USART_Cmd(USART1, ENABLE);
+ /* Enable the USART2 */
+ USART_Cmd(USART2, ENABLE);
+
+ /* Wait until end of transmission from USART1 to USART2 */
+ while(RxCounter2 < RxBufferSize2)
+ {
+ }
+
+ /* Wait until end of transmission from USART2 to USART1 */
+ while(RxCounter1 < RxBufferSize1)
+ {
+ }
+
+ /* Check the received data with the send ones */
+ TransferStatus1 = Buffercmp(TxBuffer2, RxBuffer1, RxBufferSize1);
+ /* TransferStatus1 = PASSED, if the data transmitted from USART2 and
+ received by USART1 are the same */
+ /* TransferStatus1 = FAILED, if the data transmitted from USART2 and
+ received by USART1 are different */
+ TransferStatus2 = Buffercmp(TxBuffer1, RxBuffer2, RxBufferSize2);
+ /* TransferStatus2 = PASSED, if the data transmitted from USART1 and
+ received by USART2 are the same */
+ /* TransferStatus2 = FAILED, if the data transmitted from USART1 and
+ received by USART2 are different */
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable USART1, GPIOA, GPIOx and AFIO clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOx
+ | RCC_APB2Periph_AFIO, ENABLE);
+ /* Enable USART2 clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+#ifdef USE_STM3210B_EVAL
+ /* Enable the USART2 Pins Software Remapping */
+ GPIO_PinRemapConfig(GPIO_Remap_USART2, ENABLE);
+#endif
+
+ /* Configure USART1 Rx (PA.10) as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART2 Rx as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_RxPin;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+
+ /* Configure USART1 Tx (PA.09) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART2 Tx as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_TxPin;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Configure the NVIC Preemption Priority Bits */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_0);
+
+ /* Enable the USART1 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Enable the USART2 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Interrupt/platform_config.h b/src/stm32lib/examples/USART/Interrupt/platform_config.h new file mode 100755 index 0000000..14ceaf4 --- /dev/null +++ b/src/stm32lib/examples/USART/Interrupt/platform_config.h @@ -0,0 +1,48 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+#define GPIOx GPIOD
+#define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOD
+#define GPIO_TxPin GPIO_Pin_5
+#define GPIO_RxPin GPIO_Pin_6
+#elif defined USE_STM3210E_EVAL
+#define GPIOx GPIOA
+#define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOA
+#define GPIO_TxPin GPIO_Pin_2
+#define GPIO_RxPin GPIO_Pin_3
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Interrupt/readme.txt b/src/stm32lib/examples/USART/Interrupt/readme.txt new file mode 100755 index 0000000..0496430 --- /dev/null +++ b/src/stm32lib/examples/USART/Interrupt/readme.txt @@ -0,0 +1,73 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the USART Interrupts Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a basic communication between USART1 and USART2 using
+interrupts.
+USART2 sends TxBuffer2 to USART1 which sends TxBuffer1 to USART2. The data received
+by USART1 and USART2 are stored respectively in RxBuffer1 and RxBuffer2. The data
+transfer is managed in USART1_IRQHandler and USART2_IRQHandler in stm32f10x_it.c file.
+
+USART1 and USART2 configured as follow:
+ - BaudRate = 9600 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Connect a null-modem female/female RS232 cable between CN5 and CN6.
+ - Note: in this case USART2 Tx and Rx pins are remapped by software on
+ PD.05 and PD.06 respectively.
+
+ + STM3210E-EVAL
+ - Connect a null-modem female/female RS232 cable between CN12 and CN8.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_usart.c
+ + stm32f10x_gpio.c
+ + stm32f10x_nvic.c
+ + stm32f10x_rcc.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/USART/Interrupt/stm32f10x_conf.h b/src/stm32lib/examples/USART/Interrupt/stm32f10x_conf.h new file mode 100755 index 0000000..0a79cd3 --- /dev/null +++ b/src/stm32lib/examples/USART/Interrupt/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+#define _USART1
+#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Interrupt/stm32f10x_it.c b/src/stm32lib/examples/USART/Interrupt/stm32f10x_it.c new file mode 100755 index 0000000..b2e107a --- /dev/null +++ b/src/stm32lib/examples/USART/Interrupt/stm32f10x_it.c @@ -0,0 +1,869 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+extern u8 TxBuffer1[];
+extern u8 TxBuffer2[];
+extern u8 RxBuffer1[];
+extern u8 RxBuffer2[];
+extern vu8 TxCounter1;
+extern vu8 TxCounter2;
+extern vu8 RxCounter1;
+extern vu8 RxCounter2;
+extern u8 NbrOfDataToTransfer1;
+extern u8 NbrOfDataToTransfer2;
+extern u8 NbrOfDataToRead1;
+extern u8 NbrOfDataToRead2;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+ if(USART_GetITStatus(USART1, USART_IT_RXNE) != RESET)
+ {
+ /* Read one byte from the receive data register */
+ RxBuffer1[RxCounter1++] = USART_ReceiveData(USART1);
+
+ if(RxCounter1 == NbrOfDataToRead1)
+ {
+ /* Disable the USART1 Receive interrupt */
+ USART_ITConfig(USART1, USART_IT_RXNE, DISABLE);
+ }
+ }
+
+ if(USART_GetITStatus(USART1, USART_IT_TXE) != RESET)
+ {
+ /* Write one byte to the transmit data register */
+ USART_SendData(USART1, TxBuffer1[TxCounter1++]);
+
+ if(TxCounter1 == NbrOfDataToTransfer1)
+ {
+ /* Disable the USART1 Transmit interrupt */
+ USART_ITConfig(USART1, USART_IT_TXE, DISABLE);
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+ if(USART_GetITStatus(USART2, USART_IT_RXNE) != RESET)
+ {
+ /* Read one byte from the receive data register */
+ RxBuffer2[RxCounter2++] = USART_ReceiveData(USART2);
+
+ if(RxCounter2 == NbrOfDataToRead1)
+ {
+ /* Disable the USART2 Receive interrupt */
+ USART_ITConfig(USART2, USART_IT_RXNE, DISABLE);
+ }
+ }
+
+ if(USART_GetITStatus(USART2, USART_IT_TXE) != RESET)
+ {
+ /* Write one byte to the transmit data register */
+ USART_SendData(USART2, TxBuffer2[TxCounter2++]);
+
+ if(TxCounter2 == NbrOfDataToTransfer2)
+ {
+ /* Disable the USART2 Transmit interrupt */
+ USART_ITConfig(USART2, USART_IT_TXE, DISABLE);
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Interrupt/stm32f10x_it.h b/src/stm32lib/examples/USART/Interrupt/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/USART/Interrupt/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/IrDA/Receive/main.c b/src/stm32lib/examples/USART/IrDA/Receive/main.c new file mode 100755 index 0000000..5338cc9 --- /dev/null +++ b/src/stm32lib/examples/USART/IrDA/Receive/main.c @@ -0,0 +1,262 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define NOKEY 0x00
+#define SEL 0x01
+#define RIGHT 0x02
+#define LEFT 0x03
+#define UP 0x04
+#define DOWN 0x05
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+USART_InitTypeDef USART_InitStructure;
+u8 ReceivedData = 0;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+/* USART3 configuration ------------------------------------------------------*/
+ /* USART3 configured as follow:
+ - BaudRate = 115200 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+ */
+ USART_InitStructure.USART_BaudRate = 115200;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_No ;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+
+
+ /* Configure the USART3 */
+ USART_Init(USART3, &USART_InitStructure);
+ /* Enable the USART3 */
+ USART_Cmd(USART3, ENABLE);
+
+ /* Set the USART3 prescaler */
+ USART_SetPrescaler(USART3, 0x1);
+ /* Configure the USART3 IrDA mode */
+ USART_IrDAConfig(USART3, USART_IrDAMode_Normal);
+
+ /* Enable the USART3 IrDA mode */
+ USART_IrDACmd(USART3, ENABLE);
+
+ while (1)
+ {
+ /* Wait until a byte is received */
+ while(USART_GetFlagStatus(USART3, USART_FLAG_RXNE) == RESET)
+ {
+ }
+ /* Read the received byte */
+ ReceivedData = USART_ReceiveData(USART3);
+
+ switch(ReceivedData)
+ {
+ case UP:
+ GPIO_Write(GPIO_LED, GPIO_Pin_6);
+ break;
+ case DOWN:
+ GPIO_Write(GPIO_LED, GPIO_Pin_7);
+ break;
+ case LEFT:
+ GPIO_Write(GPIO_LED, GPIO_Pin_8);
+ break;
+ case RIGHT:
+ GPIO_Write(GPIO_LED, GPIO_Pin_9);
+ break;
+ case SEL:
+ GPIO_Write(GPIO_LED, GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9);
+ break;
+ case NOKEY:
+ break;
+ default:
+ break;
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable GPIOC, GPIO_LED and AFIO clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC | RCC_APB2Periph_GPIO_LED |
+ RCC_APB2Periph_AFIO, ENABLE);
+ /* Enable USART3 clocks */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Enable the USART3 Pins Partial Software Remapping */
+ GPIO_PinRemapConfig(GPIO_PartialRemap_USART3, ENABLE);
+
+ /* Configure USART3 Tx (PC.10)as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+
+ /* Configure USART3 Rx PC.11 as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+
+ /* Configure GPIO_LED Pin 6, GPIO_LED Pin 7, GPIO_LED Pin 8 and GPIO_LED Pin 9 as output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/IrDA/Receive/platform_config.h b/src/stm32lib/examples/USART/IrDA/Receive/platform_config.h new file mode 100755 index 0000000..9be57f8 --- /dev/null +++ b/src/stm32lib/examples/USART/IrDA/Receive/platform_config.h @@ -0,0 +1,44 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/IrDA/Receive/readme.txt b/src/stm32lib/examples/USART/IrDA/Receive/readme.txt new file mode 100755 index 0000000..21d8a89 --- /dev/null +++ b/src/stm32lib/examples/USART/IrDA/Receive/readme.txt @@ -0,0 +1,85 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the USART IrDA Receive Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a basic communication USART3 IrDA receive mode. Four leds
+are used to show which byte is received.
+
+ - LD1 toggle when 0x04 is received
+ - LD2 toggle when 0x05 is received
+ - LD3 toggle when 0x03 is received
+ - LD4 toggle when 0x02 is received
+ - LD1, LD2, LD3 and LD4 toggle when 0x01 is received
+
+USART3 configured as follow:
+ - BaudRate = 115200 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+
+The USART IrDA example provides two IrDA program: transmitter&receiver and requires two boards
+to be able to run the full demonstration:
+ - one board will act as IrDA transmitter
+ - one board will act as IrDA receiver
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use an IrDA tranceiver connected to the USART3 Tx pin (U11 connector, JP5
+ jumper must be fitted).
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PC.06, PC.07, PC.08
+ and PC.09 pins
+
+ + STM3210E-EVAL
+ - Use an IrDA tranceiver connected to the USART3 Tx pin (U13 connector, JP21
+ and JP22 jumper must be fitted).
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PF.06, PF0.7, PF.08
+ and PF.09 pins
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_usart.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/USART/IrDA/Receive/stm32f10x_conf.h b/src/stm32lib/examples/USART/IrDA/Receive/stm32f10x_conf.h new file mode 100755 index 0000000..905bcdc --- /dev/null +++ b/src/stm32lib/examples/USART/IrDA/Receive/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+//#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+//#define _USART1
+//#define _USART2
+#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/IrDA/Receive/stm32f10x_it.c b/src/stm32lib/examples/USART/IrDA/Receive/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/USART/IrDA/Receive/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/IrDA/Receive/stm32f10x_it.h b/src/stm32lib/examples/USART/IrDA/Receive/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/USART/IrDA/Receive/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/IrDA/Transmit/main.c b/src/stm32lib/examples/USART/IrDA/Transmit/main.c new file mode 100755 index 0000000..7e11ee9 --- /dev/null +++ b/src/stm32lib/examples/USART/IrDA/Transmit/main.c @@ -0,0 +1,340 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define NOKEY 0
+#define SEL 1
+#define RIGHT 2
+#define LEFT 3
+#define UP 4
+#define DOWN 5
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+USART_InitTypeDef USART_InitStructure;
+u8 MyKey = 0;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+u8 ReadKey(void);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+/* USART3 configuration ------------------------------------------------------*/
+ /* USART3 configured as follow:
+ - BaudRate = 115200 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+ */
+ USART_InitStructure.USART_BaudRate = 115200;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_No ;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+
+ /* Configure the USART3 */
+ USART_Init(USART3, &USART_InitStructure);
+ /* Enable the USART3 */
+ USART_Cmd(USART3, ENABLE);
+ /* Set the USART3 prescaler */
+ USART_SetPrescaler(USART3, 0x1);
+ /* Configure the USART3 IrDA mode */
+ USART_IrDAConfig(USART3, USART_IrDAMode_Normal);
+
+ /* Enable the USART3 IrDA mode */
+ USART_IrDACmd(USART3, ENABLE);
+
+
+ while (1)
+ {
+ /* Read Key */
+ MyKey = ReadKey();
+
+ switch(MyKey)
+ {
+ case UP:
+ USART_SendData(USART3, UP);
+ while(USART_GetFlagStatus(USART3, USART_FLAG_TXE) == RESET)
+ {
+ }
+ break;
+ case DOWN:
+ USART_SendData(USART3, DOWN);
+ while(USART_GetFlagStatus(USART3, USART_FLAG_TXE) == RESET)
+ {
+ }
+ break;
+ case LEFT:
+ USART_SendData(USART3, LEFT);
+ while(USART_GetFlagStatus(USART3, USART_FLAG_TXE) == RESET)
+ {
+ }
+ break;
+ case RIGHT:
+ USART_SendData(USART3, RIGHT);
+ while(USART_GetFlagStatus(USART3, USART_FLAG_TXE) == RESET)
+ {
+ }
+ break;
+ case SEL:
+ USART_SendData(USART3, SEL);
+ while(USART_GetFlagStatus(USART3, USART_FLAG_TXE) == RESET)
+ {
+ }
+ break;
+ case NOKEY:
+ USART_SendData(USART3, NOKEY);
+ while(USART_GetFlagStatus(USART3, USART_FLAG_TXE) == RESET)
+ {
+ }
+ break;
+ default:
+ break;
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable GPIOC, GPIO Right Button, GPIO Left Button, GPIO UP Button
+ GPIO DOWN Button, GPIO SEL Button and AFIO clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC | RCC_APB2Periph_GPIO_RIGHT_BUTTON
+ | RCC_APB2Periph_GPIO_LEFT_BUTTON | RCC_APB2Periph_GPIO_UP_BUTTON
+ |RCC_APB2Periph_GPIO_DOWN_BUTTON | RCC_APB2Periph_GPIO_SEL_BUTTON
+ | RCC_APB2Periph_AFIO, ENABLE);
+ /* Enable USART3 clocks */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure the USART3 Software Pins remapping */
+ GPIO_PinRemapConfig(GPIO_PartialRemap_USART3, ENABLE);
+
+ /* Configure USART3 Tx (PC.10)as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+
+ /* Configure USART3 Rx PC.11 as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+
+ /* Configure GPIO RIGHT Button Pin as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_RIGHT_BUTTON;
+ GPIO_Init(GPIO_RIGHT_BUTTON, &GPIO_InitStructure);
+
+ /* Configure GPIO LEFT Button Pin as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_LEFT_BUTTON;
+ GPIO_Init(GPIO_LEFT_BUTTON, &GPIO_InitStructure);
+
+ /* Configure GPIO UP Button Pin as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_UP_BUTTON;
+ GPIO_Init(GPIO_UP_BUTTON, &GPIO_InitStructure);
+
+ /* Configure GPIO DOWN Button Pin as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_DOWN_BUTTON;
+ GPIO_Init(GPIO_DOWN_BUTTON, &GPIO_InitStructure);
+
+ /* Configure GPIO SEL Button Pin as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_SEL_BUTTON;
+ GPIO_Init(GPIO_SEL_BUTTON, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : ReadKey
+* Description : Reads key from demoboard.
+* Input : None
+* Output : None
+* Return : Return RIGHT, LEFT, SEL, UP, DOWN or NOKEY
+*******************************************************************************/
+u8 ReadKey(void)
+{
+ /* "right" key is pressed */
+ if(!GPIO_ReadInputDataBit(GPIO_RIGHT_BUTTON, GPIO_PIN_RIGHT_BUTTON))
+ {
+ while(GPIO_ReadInputDataBit(GPIO_RIGHT_BUTTON, GPIO_PIN_RIGHT_BUTTON) == Bit_RESET);
+ return RIGHT;
+ }
+ /* "left" key is pressed */
+ if(!GPIO_ReadInputDataBit(GPIO_LEFT_BUTTON, GPIO_PIN_LEFT_BUTTON))
+ {
+ while(GPIO_ReadInputDataBit(GPIO_LEFT_BUTTON, GPIO_PIN_LEFT_BUTTON) == Bit_RESET);
+ return LEFT;
+ }
+ /* "up" key is pressed */
+ if(!GPIO_ReadInputDataBit(GPIO_UP_BUTTON, GPIO_PIN_UP_BUTTON))
+ {
+ while(GPIO_ReadInputDataBit(GPIO_UP_BUTTON, GPIO_PIN_UP_BUTTON) == Bit_RESET);
+ return UP;
+ }
+ /* "down" key is pressed */
+ if(!GPIO_ReadInputDataBit(GPIO_DOWN_BUTTON, GPIO_PIN_DOWN_BUTTON))
+ {
+ while(GPIO_ReadInputDataBit(GPIO_DOWN_BUTTON, GPIO_PIN_DOWN_BUTTON) == Bit_RESET);
+ return DOWN;
+ }
+ /* "sel" key is pressed */
+ if(!GPIO_ReadInputDataBit(GPIO_SEL_BUTTON, GPIO_PIN_SEL_BUTTON))
+ {
+ while(GPIO_ReadInputDataBit(GPIO_SEL_BUTTON, GPIO_PIN_SEL_BUTTON) == Bit_RESET);
+ return SEL;
+ }
+ /* No key is pressed */
+ else
+ {
+ return NOKEY;
+ }
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/IrDA/Transmit/platform_config.h b/src/stm32lib/examples/USART/IrDA/Transmit/platform_config.h new file mode 100755 index 0000000..deaf7b4 --- /dev/null +++ b/src/stm32lib/examples/USART/IrDA/Transmit/platform_config.h @@ -0,0 +1,70 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define RCC_APB2Periph_GPIO_RIGHT_BUTTON RCC_APB2Periph_GPIOE
+ #define GPIO_RIGHT_BUTTON GPIOE
+ #define GPIO_PIN_RIGHT_BUTTON GPIO_Pin_0
+ #define RCC_APB2Periph_GPIO_LEFT_BUTTON RCC_APB2Periph_GPIOE
+ #define GPIO_LEFT_BUTTON GPIOE
+ #define GPIO_PIN_LEFT_BUTTON GPIO_Pin_1
+ #define RCC_APB2Periph_GPIO_UP_BUTTON RCC_APB2Periph_GPIOD
+ #define GPIO_UP_BUTTON GPIOD
+ #define GPIO_PIN_UP_BUTTON GPIO_Pin_8
+ #define RCC_APB2Periph_GPIO_DOWN_BUTTON RCC_APB2Periph_GPIOD
+ #define GPIO_DOWN_BUTTON GPIOD
+ #define GPIO_PIN_DOWN_BUTTON GPIO_Pin_14
+ #define RCC_APB2Periph_GPIO_SEL_BUTTON RCC_APB2Periph_GPIOD
+ #define GPIO_SEL_BUTTON GPIOD
+ #define GPIO_PIN_SEL_BUTTON GPIO_Pin_12
+#elif defined USE_STM3210E_EVAL
+ #define RCC_APB2Periph_GPIO_RIGHT_BUTTON RCC_APB2Periph_GPIOG
+ #define GPIO_RIGHT_BUTTON GPIOG
+ #define GPIO_PIN_RIGHT_BUTTON GPIO_Pin_13
+ #define RCC_APB2Periph_GPIO_LEFT_BUTTON RCC_APB2Periph_GPIOG
+ #define GPIO_LEFT_BUTTON GPIOG
+ #define GPIO_PIN_LEFT_BUTTON GPIO_Pin_14
+ #define RCC_APB2Periph_GPIO_UP_BUTTON RCC_APB2Periph_GPIOG
+ #define GPIO_UP_BUTTON GPIOG
+ #define GPIO_PIN_UP_BUTTON GPIO_Pin_15
+ #define RCC_APB2Periph_GPIO_DOWN_BUTTON RCC_APB2Periph_GPIOD
+ #define GPIO_DOWN_BUTTON GPIOD
+ #define GPIO_PIN_DOWN_BUTTON GPIO_Pin_3
+ #define RCC_APB2Periph_GPIO_SEL_BUTTON RCC_APB2Periph_GPIOG
+ #define GPIO_SEL_BUTTON GPIOG
+ #define GPIO_PIN_SEL_BUTTON GPIO_Pin_7
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/IrDA/Transmit/readme.txt b/src/stm32lib/examples/USART/IrDA/Transmit/readme.txt new file mode 100755 index 0000000..e5dd1e2 --- /dev/null +++ b/src/stm32lib/examples/USART/IrDA/Transmit/readme.txt @@ -0,0 +1,94 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the USART IrDA Transmit Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a basic communication USART3 IrDA transmit mode. Five pins,
+configured in input floating mode, are used to select the byte to be send at
+each pin state change.
+
+These bytes are:
+ - 0x00 if no key pressed
+ - 0x01 if SEL pin state change
+ - 0x02 if RIGHT pin state change
+ - 0x03 if LEFT pin state change
+ - 0x04 if UP pin state change
+ - 0x05 if DOWN pin state change
+
+USART3 configured as follow:
+ - BaudRate = 115200 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+
+The USART IrDA example provides two IrDA program: transmitter&receiver and requires two boards
+to be able to run the full demonstration:
+ - one board will act as IrDA transmitter
+ - one board will act as IrDA receiver
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use DOWN push-button connected to pin PD.14
+ - Use UP push-button connected to pin PD.08
+ - Use SEL push-button connected to pin PD.12
+ - Use RIGHT push-button connected to pin PE.00
+ - Use RIGHT push-button connected to pin PE.01
+ - Use an IrDA tranceiver connected to the USART3 Tx pin (U11 connector, JP5
+ jumper must be fitted).
+
+ + STM3210E-EVAL
+ - Use DOWN push-button connected to pin PD.03
+ - Use UP push-button connected to pin PG.15
+ - Use SEL push-button connected to pin PG.07
+ - Use RIGHT push-button connected to pin PG.13
+ - Use RIGHT push-button connected to pin PG.14
+ - Use an IrDA tranceiver connected to the USART3 Tx pin (U13 connector, JP21
+ and JP22 jumper must be fitted).
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_usart.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/USART/IrDA/Transmit/stm32f10x_conf.h b/src/stm32lib/examples/USART/IrDA/Transmit/stm32f10x_conf.h new file mode 100755 index 0000000..c0eac93 --- /dev/null +++ b/src/stm32lib/examples/USART/IrDA/Transmit/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+#define _GPIOD
+#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+//#define _USART1
+//#define _USART2
+#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/IrDA/Transmit/stm32f10x_it.c b/src/stm32lib/examples/USART/IrDA/Transmit/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/USART/IrDA/Transmit/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/IrDA/Transmit/stm32f10x_it.h b/src/stm32lib/examples/USART/IrDA/Transmit/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/USART/IrDA/Transmit/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/MultiProcessor/main.c b/src/stm32lib/examples/USART/MultiProcessor/main.c new file mode 100755 index 0000000..3003853 --- /dev/null +++ b/src/stm32lib/examples/USART/MultiProcessor/main.c @@ -0,0 +1,333 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+USART_InitTypeDef USART_InitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void EXTI_Configuration(void);
+void NVIC_Configuration(void);
+void Delay(u32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+ /* Configure the EXTI Controller */
+ EXTI_Configuration();
+
+/* USART1 and USART2 configuration ------------------------------------------------------*/
+ /* USART and USART2 configured as follow:
+ - BaudRate = 9600 baud
+ - Word Length = 9 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+ */
+ USART_InitStructure.USART_BaudRate = 9600;
+ USART_InitStructure.USART_WordLength = USART_WordLength_9b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_No;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+
+ /* Configure USART1 */
+ USART_Init(USART1, &USART_InitStructure);
+ /* Configure USART2 */
+ USART_Init(USART2, &USART_InitStructure);
+
+ /* Enable the USART1 */
+ USART_Cmd(USART1, ENABLE);
+ /* Enable the USART2 */
+ USART_Cmd(USART2, ENABLE);
+
+ /* Set the USART1 Address */
+ USART_SetAddress(USART1, 0x1);
+ /* Set the USART2 Address */
+ USART_SetAddress(USART2, 0x2);
+
+ /* Select the USART2 WakeUp Method */
+ USART_WakeUpConfig(USART2, USART_WakeUp_AddressMark);
+
+ while (1)
+ {
+ /* Send one byte from USART1 to USART 2 */
+ USART_SendData(USART1, 0x33);
+ /* Wait while USART1 TXE = 0 */
+ while(USART_GetFlagStatus(USART1, USART_FLAG_TXE) == RESET)
+ {
+ }
+ if(USART_GetFlagStatus(USART2, USART_FLAG_RXNE) != RESET)
+ {
+ if(USART_ReceiveData(USART2) == 0x33)
+ {
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_6, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_6)));
+ Delay(0x5FFFF);
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_7, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_7)));
+ Delay(0x5FFFF);
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_8, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_8)));
+ Delay(0x5FFFF);
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_9, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_9)));
+ Delay(0x5FFFF);
+ }
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable USART1, GPIOA, GPIO_KEY_BUTTON, GPIO_LED, GPIOx and AFIO clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA |
+ RCC_APB2Periph_GPIO_KEY_BUTTON | RCC_APB2Periph_GPIO_LED |
+ RCC_APB2Periph_GPIOx | RCC_APB2Periph_AFIO, ENABLE);
+ /* Enable USART2 clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+#ifdef USE_STM3210B_EVAL
+ /* Enable the USART2 Pins Software Remapping */
+ GPIO_PinRemapConfig(GPIO_Remap_USART2, ENABLE);
+#endif
+
+ /* Configure GPIO_LED Pin 6, GPIO_LED Pin 7, GPIO_LED Pin 8 and GPIO_LED Pin 9 as output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ /* Configure USART1 Tx (PA.09) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART2 Tx as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_TxPin;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+
+ /* Configure USART1 Rx (PA.10) as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART2 Rx as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_RxPin;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+
+ /* Configure PA.00 as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure Key Button GPIO Pin as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_KEY_BUTTON;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIO_KEY_BUTTON, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : EXTI_Configuration
+* Description : Configures the External Interrupts controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_Configuration(void)
+{
+ EXTI_InitTypeDef EXTI_InitStructure;
+
+ /* Connect Key Button EXTI Line to Key Button GPIO Pin */
+ GPIO_EXTILineConfig(GPIO_PORT_SOURCE_KEY_BUTTON, GPIO_PIN_SOURCE_KEY_BUTTON);
+
+ /* Configure Key Button EXTI Line to generate an interrupt on falling edge */
+ EXTI_InitStructure.EXTI_Line = EXTI_LINE_KEY_BUTTON;
+ EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
+ EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+ EXTI_Init(&EXTI_InitStructure);
+
+ /* Connect EXTI Line0 to PA.00 */
+ GPIO_EXTILineConfig(GPIO_PortSourceGPIOA, GPIO_PinSource0);
+ /* Configure EXTI Line0 to generate an interrupt on rising edge */
+ EXTI_InitStructure.EXTI_Line = EXTI_Line0;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
+ EXTI_Init(&EXTI_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Configure the NVIC Preemption Priority Bits */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
+
+ /* Enable the Key Button EXTI Line Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = EXTI9_5_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ /* Enable the EXTI Line 0 Interrupt */
+ NVIC_InitStructure.NVIC_IRQChannel = EXTI0_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(u32 nCount)
+{
+ /* Decrement nCount value */
+ for(; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/MultiProcessor/platform_config.h b/src/stm32lib/examples/USART/MultiProcessor/platform_config.h new file mode 100755 index 0000000..34ea30e --- /dev/null +++ b/src/stm32lib/examples/USART/MultiProcessor/platform_config.h @@ -0,0 +1,64 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIOx GPIOD
+ #define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOD
+ #define GPIO_TxPin GPIO_Pin_5
+ #define GPIO_RxPin GPIO_Pin_6
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+ #define GPIO_KEY_BUTTON GPIOB
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOB
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_9
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line9
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOB
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource9
+#elif defined USE_STM3210E_EVAL
+ #define GPIOx GPIOA
+ #define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOA
+ #define GPIO_TxPin GPIO_Pin_2
+ #define GPIO_RxPin GPIO_Pin_3
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+ #define GPIO_KEY_BUTTON GPIOG
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOG
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_8
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line8
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOG
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource8
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/MultiProcessor/readme.txt b/src/stm32lib/examples/USART/MultiProcessor/readme.txt new file mode 100755 index 0000000..dd3c62f --- /dev/null +++ b/src/stm32lib/examples/USART/MultiProcessor/readme.txt @@ -0,0 +1,87 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the USART Multi Processor Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to use the USART in multi-processor mode.
+First, the USART1 and USART2 address are set to 0x1 and 0x2. The USART1 send
+continusouly the character 0x33 to the USART2. The USART2 toggle LD1, LD2, LD3
+and LD4 pins while receiving 0x33.
+
+When a falling edge is applied on Key Button EXTI line, an interrupt is generated
+and in the EXTI9_5_IRQHandler routine, the USART2 is entred in mute mode and still
+in this mode (no LED toggling) until a rising edge is applied on EXTI Line 0.
+In this interrupt routine the USART1 send the character of address mark (0x102)
+to wakeup USART2. The LED restart toggling.
+
+USART1 and USART2 configured as follow:
+ - BaudRate = 9600 baud
+ - Word Length = 9 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Connect a null-modem female/female RS232 cable between CN5 and CN6.
+ - Note: in this case USART2 Tx and Rx pins are remapped by software on
+ PD.05 and PD.06 respectively.
+ - Use Key push-button connected to pin PB.09 (EXTI Line9)
+ - Use Wakeup push-button connected to pin PA.00 (EXTI Line0)
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PC.06, PC.07, PC.08
+ and PC.09 pins
+
+ + STM3210E-EVAL
+ - Connect a null-modem female/female RS232 cable between CN12 and CN8.
+ - Use Key push-button connected to pin PG.08 (EXTI Line8)
+ - Use Wakeup push-button connected to pin PA.00 (EXTI Line0)
+ - Use LD1, LD2, LD3 and LD4 leds connected respectively to PF.06, PF0.7, PF.08
+ and PF.09 pins
+ - Make sure that the Jumper 4 (JP4) is in position 1<-->2.
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_usart.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_exti.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/USART/MultiProcessor/stm32f10x_conf.h b/src/stm32lib/examples/USART/MultiProcessor/stm32f10x_conf.h new file mode 100755 index 0000000..6c9050c --- /dev/null +++ b/src/stm32lib/examples/USART/MultiProcessor/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+#define _USART1
+#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/MultiProcessor/stm32f10x_it.c b/src/stm32lib/examples/USART/MultiProcessor/stm32f10x_it.c new file mode 100755 index 0000000..fd242e6 --- /dev/null +++ b/src/stm32lib/examples/USART/MultiProcessor/stm32f10x_it.c @@ -0,0 +1,834 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+ /* Send the address mark (0x102) to wakeup USART2 */
+ USART_SendData(USART1, 0x102);
+
+ /* Wait while USART1 TXE = 0 */
+ while(USART_GetFlagStatus(USART1, USART_FLAG_TXE) == RESET)
+ {
+ }
+
+ /* Clear EXTI Line 0 Pending Bit */
+ EXTI_ClearITPendingBit(EXTI_Line0);
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+ if(EXTI_GetITStatus(EXTI_LINE_KEY_BUTTON) != RESET)
+ {
+ /* Flush DR register */
+ USART_ReceiveData(USART2);
+ /* Clear the USART2 RXNE Flag */
+ USART_ClearFlag(USART2, USART_FLAG_RXNE);
+
+ /* Enable the USART2 mute mode*/
+ USART_ReceiverWakeUpCmd(USART2, ENABLE);
+
+ /* Clear Key Button EXTI Line Pending Bit */
+ EXTI_ClearITPendingBit(EXTI_LINE_KEY_BUTTON);
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/MultiProcessor/stm32f10x_it.h b/src/stm32lib/examples/USART/MultiProcessor/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/USART/MultiProcessor/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Polling/main.c b/src/stm32lib/examples/USART/Polling/main.c new file mode 100755 index 0000000..3c5aca1 --- /dev/null +++ b/src/stm32lib/examples/USART/Polling/main.c @@ -0,0 +1,289 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum { FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define TxBufferSize (countof(TxBuffer))
+
+/* Private macro -------------------------------------------------------------*/
+#define countof(a) (sizeof(a) / sizeof(*(a)))
+
+/* Private variables ---------------------------------------------------------*/
+USART_InitTypeDef USART_InitStructure;
+u8 TxBuffer[] = "Buffer Send from USART1 to USART2 using Flags";
+u8 RxBuffer[TxBufferSize];
+u8 TxCounter = 0, RxCounter = 0;
+TestStatus TransferStatus = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength);
+u8 index = 0;
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+/* USART1 and USART2 configuration ------------------------------------------------------*/
+ /* USART and USART2 configured as follow:
+ - BaudRate = 230400 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - Even parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+ */
+ USART_InitStructure.USART_BaudRate = 230400;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_Even;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+
+ /* Configure USART1 */
+ USART_Init(USART1, &USART_InitStructure);
+ /* Configure USART2 */
+ USART_Init(USART2, &USART_InitStructure);
+
+ /* Enable the USART1 */
+ USART_Cmd(USART1, ENABLE);
+
+ /* Enable the USART2 */
+ USART_Cmd(USART2, ENABLE);
+
+ while(TxCounter < TxBufferSize)
+ {
+ /* Send one byte from USART1 to USART2 */
+ USART_SendData(USART1, TxBuffer[TxCounter++]);
+
+ /* Loop until the end of transmit */
+ while(USART_GetFlagStatus(USART1, USART_FLAG_TC) == RESET)
+ {
+ }
+
+ /* Loop until the USART2 Receive Data Register is not empty */
+ while(USART_GetFlagStatus(USART2, USART_FLAG_RXNE) == RESET)
+ {
+ }
+
+ /* Store the received byte in RxBuffer */
+ RxBuffer[RxCounter++] = (USART_ReceiveData(USART2) & 0x7F);
+
+ }
+ /* Check the received data with the send ones */
+ TransferStatus = Buffercmp(TxBuffer, RxBuffer, TxBufferSize);
+ /* TransferStatus = PASSED, if the data transmitted from USART1 and
+ received by USART2 are the same */
+ /* TransferStatus = FAILED, if the data transmitted from USART1 and
+ received by USART2 are different */
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable USART1, GPIOA, GPIOD and AFIO clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA |RCC_APB2Periph_GPIOx
+ | RCC_APB2Periph_AFIO, ENABLE);
+ /* Enable USART2 clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+#ifdef USE_STM3210B_EVAL
+ /* Enable the USART2 Pins Software Remapping */
+ GPIO_PinRemapConfig(GPIO_Remap_USART2, ENABLE);
+#endif
+
+ /* Configure USART1 Tx (PA.09) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART2 Tx as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_TxPin;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+
+ /* Configure USART1 Rx (PA.10) as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART2 Rx as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_RxPin;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Polling/platform_config.h b/src/stm32lib/examples/USART/Polling/platform_config.h new file mode 100755 index 0000000..14ceaf4 --- /dev/null +++ b/src/stm32lib/examples/USART/Polling/platform_config.h @@ -0,0 +1,48 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+#define GPIOx GPIOD
+#define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOD
+#define GPIO_TxPin GPIO_Pin_5
+#define GPIO_RxPin GPIO_Pin_6
+#elif defined USE_STM3210E_EVAL
+#define GPIOx GPIOA
+#define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOA
+#define GPIO_TxPin GPIO_Pin_2
+#define GPIO_RxPin GPIO_Pin_3
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Polling/readme.txt b/src/stm32lib/examples/USART/Polling/readme.txt new file mode 100755 index 0000000..8d3f496 --- /dev/null +++ b/src/stm32lib/examples/USART/Polling/readme.txt @@ -0,0 +1,73 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the USART Polling Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a basic communication between USART1 and USART2 using flags.
+First, the USART1 sends TxBuffer to USART2. The USART2 reads the received data and
+store it into RxBuffer.
+The received data is then compared with the send ones and the result of this
+comparison is stored in the "TransferStatus" variable.
+
+USART1 and USART2 configured as follow:
+ - BaudRate = 230400 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - Even parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Connect a null-modem female/female RS232 cable between CN5 and CN6.
+ - Note: in this case USART2 Tx and Rx pins are remapped by software on
+ PD.05 and PD.06 respectively.
+
+ + STM3210E-EVAL
+ - Connect a null-modem female/female RS232 cable between CN12 and CN8.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_usart.c
+ + stm32f10x_gpio.c
+ + stm32f10x_nvic.c
+ + stm32f10x_rcc.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/USART/Polling/stm32f10x_conf.h b/src/stm32lib/examples/USART/Polling/stm32f10x_conf.h new file mode 100755 index 0000000..0a79cd3 --- /dev/null +++ b/src/stm32lib/examples/USART/Polling/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+#define _USART1
+#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Polling/stm32f10x_it.c b/src/stm32lib/examples/USART/Polling/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/USART/Polling/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Polling/stm32f10x_it.h b/src/stm32lib/examples/USART/Polling/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/USART/Polling/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Printf/main.c b/src/stm32lib/examples/USART/Printf/main.c new file mode 100755 index 0000000..576e309 --- /dev/null +++ b/src/stm32lib/examples/USART/Printf/main.c @@ -0,0 +1,252 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "stdio.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+USART_InitTypeDef USART_InitStructure;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+
+#ifdef __GNUC__
+ /* With GCC/RAISONANCE, small printf (option LD Linker->Libraries->Small printf
+ set to 'Yes') calls __io_putchar() */
+ #define PUTCHAR_PROTOTYPE int __io_putchar(int ch)
+#else
+ #define PUTCHAR_PROTOTYPE int fputc(int ch, FILE *f)
+#endif /* __GNUC__ */
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+/* USARTx configuration ------------------------------------------------------*/
+ /* USARTx configured as follow:
+ - BaudRate = 115200 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+ */
+ USART_InitStructure.USART_BaudRate = 115200;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_No ;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+
+ /* Configure the USARTx */
+ USART_Init(USARTx, &USART_InitStructure);
+ /* Enable the USARTx */
+ USART_Cmd(USARTx, ENABLE);
+
+ /* Output a message on Hyperterminal using printf function */
+ printf("\n\rUSART Printf Example: retarget the C library printf function to the USART\n\r");
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable GPIOx clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOx, ENABLE);
+
+/* Enable USARTx clocks */
+#ifdef USE_USART1
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
+#else
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USARTx, ENABLE);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+#if defined USE_USART2 && defined USE_STM3210B_EVAL
+ /* Enable AFIO clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
+
+ /* Enable the USART2 Pins Software Remapping */
+ GPIO_PinRemapConfig(GPIO_Remap_USART2, ENABLE);
+#endif
+
+ /* Configure USARTx_Tx as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_TxPin;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+
+ /* Configure USARTx_Rx as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_RxPin;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOx, &GPIO_InitStructure);
+
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : PUTCHAR_PROTOTYPE
+* Description : Retargets the C library printf function to the USART.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+PUTCHAR_PROTOTYPE
+{
+ /* Write a character to the USART */
+ USART_SendData(USARTx, (u8) ch);
+
+ /* Loop until the end of transmission */
+ while(USART_GetFlagStatus(USARTx, USART_FLAG_TXE) == RESET)
+ {
+ }
+
+ return ch;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Printf/platform_config.h b/src/stm32lib/examples/USART/Printf/platform_config.h new file mode 100755 index 0000000..c8351e0 --- /dev/null +++ b/src/stm32lib/examples/USART/Printf/platform_config.h @@ -0,0 +1,86 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Uncomment the line corresponding to the select the USART used to run
+ the example */
+#define USE_USART1
+//#define USE_USART2
+//#define USE_USART3
+//#define USE_UART4
+//#define USE_UART5
+
+#ifdef USE_USART1
+ #define USARTx USART1
+ #define GPIOx GPIOA
+ #define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOA
+ #define GPIO_RxPin GPIO_Pin_10
+ #define GPIO_TxPin GPIO_Pin_9
+#elif defined USE_USART2 && defined USE_STM3210B_EVAL
+ #define USARTx USART2
+ #define RCC_APB1Periph_USARTx RCC_APB1Periph_USART2
+ #define GPIOx GPIOD
+ #define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOD
+ #define GPIO_TxPin GPIO_Pin_5
+ #define GPIO_RxPin GPIO_Pin_6
+#elif defined USE_USART2 && defined USE_STM3210E_EVAL
+ #define USARTx USART2
+ #define RCC_APB1Periph_USARTx RCC_APB1Periph_USART2
+ #define GPIOx GPIOA
+ #define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOA
+ #define GPIO_TxPin GPIO_Pin_2
+ #define GPIO_RxPin GPIO_Pin_3
+#elif defined USE_USART3
+ #define USARTx USART3
+ #define GPIOx GPIOB
+ #define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOB
+ #define RCC_APB1Periph_USARTx RCC_APB1Periph_USART3
+ #define GPIO_RxPin GPIO_Pin_11
+ #define GPIO_TxPin GPIO_Pin_10
+#elif defined USE_UART4
+ #define USARTx UART4
+ #define GPIOx GPIOC
+ #define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOC
+ #define RCC_APB1Periph_USARTx RCC_APB1Periph_UART4
+ #define GPIO_RxPin GPIO_Pin_11
+ #define GPIO_TxPin GPIO_Pin_10
+#elif defined USE_UART5
+ #define USARTx UART5
+ #define GPIOx GPIOC
+ #define RCC_APB2Periph_GPIOx RCC_APB2Periph_GPIOC
+ #define RCC_APB1Periph_USARTx RCC_APB1Periph_UART5
+ #define GPIO_RxPin GPIO_Pin_2
+ #define GPIO_TxPin GPIO_Pin_12
+#endif
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Printf/readme.txt b/src/stm32lib/examples/USART/Printf/readme.txt new file mode 100755 index 0000000..3bc3309 --- /dev/null +++ b/src/stm32lib/examples/USART/Printf/readme.txt @@ -0,0 +1,89 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the USART Printf Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to retarget the C library printf function to the USART.
+This implementation output the printf message on the Hyperterminal using USARTx.
+USARTx can be USART1, USART2, USART3, UART4 or UART5; to select the USART
+interface to be used uncomment the '#define USE_USARTx' line in 'platform_config.h'
+file.
+
+The USARTx is configured as follow:
+ - BaudRate = 115200 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + The USARTx signals (Rx, Tx) must be connected to a DB9 connector using a RS232
+ transceiver.
+
+ + Connect a null-modem female/female RS232 cable between the DB9 connector
+ and PC serial port.
+
+ + STM3210B-EVAL
+ - Connect a null-modem female/female RS232 cable between the DB9 connector
+ (CN6 for USART1, CN5 for USART2 in the STM3210B-EVAL board)
+ and PC serial port.
+
+ + STM3210E-EVAL
+ - Connect a null-modem female/female RS232 cable between the DB9 connector
+ (CN12 for USART1, CN8 for USART2 in the STM3210E-EVAL board)
+ and PC serial port.
+
+
+ - Hyperterminal configuration:
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - BaudRate = 115200 baud
+ - flow control: None
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_usart.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/USART/Printf/stm32f10x_conf.h b/src/stm32lib/examples/USART/Printf/stm32f10x_conf.h new file mode 100755 index 0000000..5fa4139 --- /dev/null +++ b/src/stm32lib/examples/USART/Printf/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+#define _USART1
+#define _USART2
+#define _USART3
+#define _UART4
+#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Printf/stm32f10x_it.c b/src/stm32lib/examples/USART/Printf/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/USART/Printf/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Printf/stm32f10x_it.h b/src/stm32lib/examples/USART/Printf/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/USART/Printf/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Smartcard/main.c b/src/stm32lib/examples/USART/Smartcard/main.c new file mode 100755 index 0000000..5f26ba4 --- /dev/null +++ b/src/stm32lib/examples/USART/Smartcard/main.c @@ -0,0 +1,444 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private define ------------------------------------------------------------*/
+#define T0_PROTOCOL 0x00 /* T0 PROTOCOL */
+#define SETUP_LENGHT 20
+#define HIST_LENGHT 20
+#define SC_Receive_Timeout 0x4000 /* direction to reader */
+
+/* Private typedef -----------------------------------------------------------*/
+/* ATR STRUCTURE - ANSWER TO RESET */
+typedef struct
+{
+ u8 TS; /* Bit Convention */
+ u8 T0; /* high nibble = N. of setup byte; low nibble = N. of historical byte */
+ u8 T[SETUP_LENGHT]; /* setup array */
+ u8 H[HIST_LENGHT]; /* historical array */
+ u8 Tlenght; /* setup array dimension */
+ u8 Hlenght; /* historical array dimension */
+} SC_ATR;
+
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+USART_InitTypeDef USART_InitStructure;
+USART_ClockInitTypeDef USART_ClockInitStructure;
+SC_ATR SC_A2R;
+vu32 index = 0, Counter = 0;
+volatile TestStatus ATRDecodeStatus = FAILED;
+vu32 CardInserted = 0, CardProtocol = 1;
+ErrorStatus HSEStartUpStatus;
+vu8 DST_Buffer[50]= {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
+ 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void EXTI_Configuration(void);
+void NVIC_Configuration(void);
+u8 SC_decode_Answer2reset(vu8 *card);
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+ /* Configure the EXTI Controller */
+ EXTI_Configuration();
+
+
+/* USART3 configuration -------------------------------------------------------*/
+ /* USART3 configured as follow:
+ - Word Length = 9 Bits
+ - 0.5 Stop Bit
+ - Even parity
+ - BaudRate = 12096 baud
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Tx and Rx enabled
+ - USART Clock enabled
+ - USART CPOL Low
+ - USART CPHA on first edge
+ - USART Last Bit Clock Enabled
+ */
+
+ /* USART Clock set to 4.5MHz (PCLK1 = 36 MHZ / 8) */
+ USART_SetPrescaler(USART3, 0x04);
+ /* USART Guard Time set to 2 Bit */
+ USART_SetGuardTime(USART3, 0x2);
+
+ USART_ClockInitStructure.USART_Clock = USART_Clock_Enable;
+ USART_ClockInitStructure.USART_CPOL = USART_CPOL_Low;
+ USART_ClockInitStructure.USART_CPHA = USART_CPHA_1Edge;
+ USART_ClockInitStructure.USART_LastBit = USART_LastBit_Enable;
+ USART_ClockInit(USART3, &USART_ClockInitStructure);
+
+ USART_InitStructure.USART_BaudRate = 12096;
+ USART_InitStructure.USART_WordLength = USART_WordLength_9b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1_5;
+ USART_InitStructure.USART_Parity = USART_Parity_Even;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_Init(USART3, &USART_InitStructure);
+
+ /* Enable the USART3 Parity Error Interrupt */
+ USART_ITConfig(USART3, USART_IT_PE, ENABLE);
+
+ /* Enable USART3 */
+ USART_Cmd(USART3, ENABLE);
+
+ /* Enable the NACK Transmission */
+ USART_SmartCardNACKCmd(USART3, ENABLE);
+
+ /* Enable the Smartcard Interface */
+ USART_SmartCardCmd(USART3, ENABLE);
+
+
+ /* Loop while no Smartcard is detected */
+ while(CardInserted == 0)
+ {
+ }
+
+ /* Read Smartcard ATR response */
+ for(index = 0; index < 40; index++, Counter = 0)
+ {
+ while((USART_GetFlagStatus(USART3, USART_FLAG_RXNE) == RESET) && (Counter != SC_Receive_Timeout))
+ {
+ Counter++;
+ }
+
+ if(Counter != SC_Receive_Timeout)
+ {
+ DST_Buffer[index] = USART_ReceiveData(USART3);
+ }
+ }
+
+ /* Decode ATR */
+ CardProtocol = SC_decode_Answer2reset(DST_Buffer);
+
+ /* Test if the inserted card is ISO7816-3 T=0 compatible */
+ if(CardProtocol == 0)
+ {
+ /* Inserted card is ISO7816-3 T=0 compatible */
+ ATRDecodeStatus = PASSED;
+ }
+ else
+ {
+ /* Inserted Smartcard is not ISO7816-3 T=0 compatible */
+ ATRDecodeStatus = FAILED;
+ }
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable GPIO_3_5V, GPIOB, GPIO_CMDVCC, GPIO_RESET, GPIO_OFF and AFIO clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_3_5V | RCC_APB2Periph_GPIOB | RCC_APB2Periph_RESET |
+ RCC_APB2Periph_CMDVCC | RCC_APB2Periph_OFF | RCC_APB2Periph_AFIO, ENABLE);
+
+ /* Enable USART3 clocks */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure USART3 CK(PB12) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* Configure USART3 Tx (PB10) as alternate function open-drain */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ /* Configure Smartcard Reset */
+ GPIO_InitStructure.GPIO_Pin = SC_RESET;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_Init(GPIO_RESET, &GPIO_InitStructure);
+
+ /* Set RSTIN HIGH */
+ GPIO_SetBits(GPIO_RESET, SC_RESET);
+
+ /* Configure Smartcard 3/5V */
+ GPIO_InitStructure.GPIO_Pin = SC_3_5V;
+ GPIO_Init(GPIO_3_5V, &GPIO_InitStructure);
+
+ /* Select 5 V */
+ GPIO_SetBits(GPIO_3_5V, SC_3_5V);
+
+ /* Configure Smartcard CMDVCC */
+ GPIO_InitStructure.GPIO_Pin = SC_CMDVCC;
+ GPIO_Init(GPIO_CMDVCC, &GPIO_InitStructure);
+
+ /* Select Smartcard CMDVCC */
+ GPIO_SetBits(GPIO_CMDVCC, SC_CMDVCC);
+
+ /* Select Smartcard OFF */
+ GPIO_InitStructure.GPIO_Pin = SC_OFF;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIO_OFF, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : EXTI_Configuration
+* Description : Configures the External Interrupts controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_Configuration(void)
+{
+ EXTI_InitTypeDef EXTI_InitStructure;
+
+ /* Smartcard OFF */
+ GPIO_EXTILineConfig(SC_PortSource, SC_PinSource);
+
+ EXTI_StructInit(&EXTI_InitStructure);
+ EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
+ EXTI_InitStructure.EXTI_Line = SC_EXTI;
+ EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+ EXTI_Init(&EXTI_InitStructure);
+
+ /* Clear SC EXTI Line Pending Bit */
+ EXTI_ClearITPendingBit(SC_EXTI);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures the nested vectored interrupt controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* Configure the NVIC Preemption Priority Bits */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
+ /* Clear the SC_EXTI IRQ Pending Bit */
+ NVIC_ClearIRQChannelPendingBit(SC_EXTI_IRQ);
+
+ NVIC_InitStructure.NVIC_IRQChannel = SC_EXTI_IRQ;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : SC_decode_Answer2reset
+* Description : Decode the Card ATR Response.
+* Input : - card: pointer to the buffer containing the Card ATR.
+* Output : None
+* Return : Card protocol
+*******************************************************************************/
+u8 SC_decode_Answer2reset(vu8 *card)
+{
+ u32 i = 0, flag = 0, buf = 0, protocol = 0;
+
+ SC_A2R.TS = 0;
+ SC_A2R.T0 = 0;
+ for (i = 0; i < SETUP_LENGHT; i++)
+ {
+ SC_A2R.T[i] = 0;
+ }
+ for (i = 0;i < HIST_LENGHT; i++)
+ {
+ SC_A2R.H[i] = 0;
+ }
+ SC_A2R.Tlenght = 0;
+ SC_A2R.Hlenght = 0;
+
+ SC_A2R.TS = card[0]; /* INITIAL CHARACTER */
+ SC_A2R.T0 = card[1]; /* FORMAT CHARACTER */
+
+ SC_A2R.Hlenght = SC_A2R.T0 & 0x0F;
+
+ if((SC_A2R.T0 & 0x80) == 0x80) flag = 1;
+
+ for(i = 0; i < 4; i++)
+ {
+ SC_A2R.Tlenght = SC_A2R.Tlenght + (((SC_A2R.T0 & 0xF0) >> (4 + i)) & 0x1);
+ }
+
+ for(i = 0; i < SC_A2R.Tlenght; i++)
+ {
+ SC_A2R.T[i] = card[i + 2];
+ }
+
+ protocol = SC_A2R.T[SC_A2R.Tlenght - 1] & 0x0F;
+
+ while(flag)
+ {
+ if ((SC_A2R.T[SC_A2R.Tlenght-1] & 0x80)== 0x80)
+ {
+ flag = 1;
+ }
+ else
+ {
+ flag = 0;
+ }
+ buf = SC_A2R.Tlenght;
+ SC_A2R.Tlenght = 0;
+
+ for(i = 0; i < 4; i++)
+ {
+ SC_A2R.Tlenght = SC_A2R.Tlenght + (((SC_A2R.T[buf - 1] & 0xF0) >> (4 + i)) & 0x1);
+ }
+ for(i = 0; i < SC_A2R.Tlenght; i++)
+ {
+ SC_A2R.T[buf + i] = card[i + 2 + buf];
+ }
+ SC_A2R.Tlenght += buf;
+ }
+
+ for(i = 0;i < SC_A2R.Hlenght; i++)
+ {
+ SC_A2R.H[i] = card[i + 2 + SC_A2R.Tlenght];
+ }
+
+ return ((u8)protocol);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Smartcard/platform_config.h b/src/stm32lib/examples/USART/Smartcard/platform_config.h new file mode 100755 index 0000000..455d148 --- /dev/null +++ b/src/stm32lib/examples/USART/Smartcard/platform_config.h @@ -0,0 +1,74 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+ //#define USE_STM3210B_EVAL
+ #define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ /* Smartcard Inteface GPIO pins */
+ #define SC_3_5V GPIO_Pin_11 /* GPIOD Pin 11 */
+ #define SC_RESET GPIO_Pin_11 /* GPIOB Pin 11 */
+ #define SC_CMDVCC GPIO_Pin_7 /* GPIOE Pin 7 */
+ #define SC_OFF GPIO_Pin_14 /* GPIOE Pin 14 */
+ #define GPIO_3_5V GPIOD
+ #define GPIO_RESET GPIOB
+ #define GPIO_CMDVCC GPIOE
+ #define GPIO_OFF GPIOE
+ #define RCC_APB2Periph_3_5V RCC_APB2Periph_GPIOD
+ #define RCC_APB2Periph_RESET RCC_APB2Periph_GPIOB
+ #define RCC_APB2Periph_CMDVCC RCC_APB2Periph_GPIOE
+ #define RCC_APB2Periph_OFF RCC_APB2Periph_GPIOE
+ #define SC_EXTI EXTI_Line14
+ #define SC_PortSource GPIO_PortSourceGPIOE
+ #define SC_PinSource GPIO_PinSource14
+ #define SC_EXTI_IRQ EXTI15_10_IRQChannel
+#elif defined USE_STM3210E_EVAL
+ /* Smartcard Inteface GPIO pins */
+ #define SC_3_5V GPIO_Pin_0 /* GPIOB Pin 0 */
+ #define SC_RESET GPIO_Pin_11 /* GPIOB Pin 11 */
+ #define SC_CMDVCC GPIO_Pin_6 /* GPIOC Pin 6 */
+ #define SC_OFF GPIO_Pin_7 /* GPIOC Pin 7 */
+ #define GPIO_3_5V GPIOB
+ #define GPIO_RESET GPIOB
+ #define GPIO_CMDVCC GPIOC
+ #define GPIO_OFF GPIOC
+ #define RCC_APB2Periph_3_5V RCC_APB2Periph_GPIOB
+ #define RCC_APB2Periph_RESET RCC_APB2Periph_GPIOB
+ #define RCC_APB2Periph_CMDVCC RCC_APB2Periph_GPIOC
+ #define RCC_APB2Periph_OFF RCC_APB2Periph_GPIOC
+ #define SC_EXTI EXTI_Line7
+ #define SC_PortSource GPIO_PortSourceGPIOC
+ #define SC_PinSource GPIO_PinSource7
+ #define SC_EXTI_IRQ EXTI9_5_IRQChannel
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Smartcard/readme.txt b/src/stm32lib/examples/USART/Smartcard/readme.txt new file mode 100755 index 0000000..615be2a --- /dev/null +++ b/src/stm32lib/examples/USART/Smartcard/readme.txt @@ -0,0 +1,87 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the USART Smartcard Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a description of how to use the USART in Smartcard mode.
+The example gives only the possibility to read the ATR and decode it into
+predefined buffer.
+First, the code is waiting for an card insertion. If a card is detected through
+the EXTI Line interrupt (connected to the Smartcard detect pin), a reset signal
+is applied to the card through its reset pin.
+As response to this reset, the card transmit the ATR which will be stored in
+predefined buffer. Once the ATR is received, it is decoded and stored in a specific
+structure (SC_A2R) and the card protocol type is stored in a variable.
+ATRDecodeStatus variable must be equal to 1 (PASSED) when the sequence succeed.
+
+The used Smartcard should be ISO7816-3 T=0 compatible.
+
+USART3 configured as follow:
+ - Word Length = 9 Bits
+ - 0.5 Stop Bit
+ - Even parity
+ - BaudRate = 12096 baud
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Tx and Rx enabled
+ - USART Clock enabled
+ - USART CPOL: Clock is active low
+ - USART CPHA: Data is captured on the second edge
+ - USART LastBit: The clock pulse of the last data bit is not output to
+ the SCLK pin
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Plug a Smartcard (ISO7816-3 T=0 compatible) into the dedicated Smartcard
+ connector CN16.
+
+ + STM3210E-EVAL
+ - Plug a Smartcard (ISO7816-3 T=0 compatible) into the dedicated Smartcard
+ connector CN18.
+ - Make sure that Jumper 15 (JP15) and Jumper 16 (JP16) are fitted.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_usart.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+ + stm32f10x_exti.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/USART/Smartcard/stm32f10x_conf.h b/src/stm32lib/examples/USART/Smartcard/stm32f10x_conf.h new file mode 100755 index 0000000..5dfe126 --- /dev/null +++ b/src/stm32lib/examples/USART/Smartcard/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+#define _GPIOD
+#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+//#define _USART1
+//#define _USART2
+#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Smartcard/stm32f10x_it.c b/src/stm32lib/examples/USART/Smartcard/stm32f10x_it.c new file mode 100755 index 0000000..3f2c264 --- /dev/null +++ b/src/stm32lib/examples/USART/Smartcard/stm32f10x_it.c @@ -0,0 +1,851 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+extern vu32 CardInserted;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+ /* Select Smart Card CMDVCC */
+ GPIO_ResetBits(GPIO_CMDVCC, SC_CMDVCC);
+
+ /* Set RSTIN LOW */
+ GPIO_ResetBits(GPIO_RESET, SC_RESET);
+
+ /* Set RSTIN HIGH */
+ GPIO_SetBits(GPIO_RESET, SC_RESET);
+
+ /* Clear SC EXTIT Line Pending Bit */
+ EXTI_ClearITPendingBit(SC_EXTI);
+
+ /* Smart card detected */
+ CardInserted = 1;
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+ /* If the USART3 detects a parity error */
+ if(USART_GetITStatus(USART3, USART_IT_PE) != RESET)
+ {
+ while(USART_GetFlagStatus(USART3, USART_FLAG_RXNE) == RESET)
+ {
+ }
+ /* Clear the USART3 Parity error pending bit */
+ USART_ClearITPendingBit(USART3, USART_IT_PE);
+ USART_ReceiveData(USART3);
+ }
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+ /* Select Smart Card CMDVCC */
+ GPIO_ResetBits(GPIO_CMDVCC, SC_CMDVCC);
+
+ /* Set RSTIN LOW */
+ GPIO_ResetBits(GPIO_RESET, SC_RESET);
+
+ /* Set RSTIN HIGH */
+ GPIO_SetBits(GPIO_RESET, SC_RESET);
+
+ /* Clear SC EXTIT Line Pending Bit */
+ EXTI_ClearITPendingBit(SC_EXTI);
+
+ /* Smart card detected */
+ CardInserted = 1;
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Smartcard/stm32f10x_it.h b/src/stm32lib/examples/USART/Smartcard/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/USART/Smartcard/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Synchronous/main.c b/src/stm32lib/examples/USART/Synchronous/main.c new file mode 100755 index 0000000..b36ae23 --- /dev/null +++ b/src/stm32lib/examples/USART/Synchronous/main.c @@ -0,0 +1,355 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+typedef enum {FAILED = 0, PASSED = !FAILED} TestStatus;
+
+/* Private define ------------------------------------------------------------*/
+#define TxBufferSize1 (countof(TxBuffer1) - 1)
+#define TxBufferSize2 (countof(TxBuffer2) - 1)
+#define DYMMY_BYTE 0x00
+
+/* Private macro -------------------------------------------------------------*/
+#define countof(a) (sizeof(a) / sizeof(*(a)))
+
+/* Private variables ---------------------------------------------------------*/
+USART_InitTypeDef USART_InitStructure;
+USART_ClockInitTypeDef USART_ClockInitStructure;
+
+u8 TxBuffer1[] = "USART Synchronous Example: USART1 -> SPI1 using TXE and RXNE Flags";
+u8 TxBuffer2[] = "USART Synchronous Example: SPI1 -> USART1 using TXE and RXNE Flags";
+u8 RxBuffer1[TxBufferSize2];
+u8 RxBuffer2[TxBufferSize1];
+u8 NbrOfDataToRead1 = TxBufferSize2;
+u8 NbrOfDataToRead2 = TxBufferSize1;
+u8 TxCounter1 = 0, RxCounter1 = 0;
+u8 TxCounter2 = 0, RxCounter2 = 0;
+volatile TestStatus TransferStatus1 = FAILED, TransferStatus2 = FAILED;
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void GPIO_Configuration(void);
+void NVIC_Configuration(void);
+void SPI_Configuration(void);
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength);
+
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : main
+* Description : Main program
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* Configure the GPIO ports */
+ GPIO_Configuration();
+
+ /* Configure the SPI */
+ SPI_Configuration();
+
+/* USART1 configuration ------------------------------------------------------*/
+ /* USART1 configured as follow:
+ - BaudRate = 115200 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+ - USART Clock Enabled
+ - USART CPOL: Clock is active High
+ - USART CPHA: Data is captured on the second edge
+ - USART LastBit: The clock pulse of the last data bit is output to
+ the SCLK pin
+ */
+ USART_ClockInitStructure.USART_Clock = USART_Clock_Enable;
+ USART_ClockInitStructure.USART_CPOL = USART_CPOL_High;
+ USART_ClockInitStructure.USART_CPHA = USART_CPHA_2Edge;
+ USART_ClockInitStructure.USART_LastBit = USART_LastBit_Enable;
+ USART_ClockInit(USART1, &USART_ClockInitStructure);
+
+ USART_InitStructure.USART_BaudRate = 115200;
+ USART_InitStructure.USART_WordLength = USART_WordLength_8b;
+ USART_InitStructure.USART_StopBits = USART_StopBits_1;
+ USART_InitStructure.USART_Parity = USART_Parity_No ;
+ USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+ USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+ USART_Init(USART1, &USART_InitStructure);
+
+ /* Configure the USART1 */
+ USART_Init(USART1, &USART_InitStructure);
+
+ /* Enable the USART1 */
+ USART_Cmd(USART1, ENABLE);
+
+ while(NbrOfDataToRead2--)
+ {
+ /* Write one byte in the USART1 Transmit Data Register */
+ USART_SendData(USART1, TxBuffer1[TxCounter1++]);
+ /* Wait until end of transmit */
+ while(USART_GetFlagStatus(USART1, USART_FLAG_TC) == RESET)
+ {
+ }
+ /* Wait the byte is entirtly received by SPI1 */
+ while(SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_RXNE) == RESET)
+ {
+ }
+ /* Store the received byte in the RxBuffer2 */
+ RxBuffer2[RxCounter2++] = SPI_I2S_ReceiveData(SPI1);
+ }
+
+ /* Clear the USART1 Data Register */
+ USART_ReceiveData(USART1);
+
+ while(NbrOfDataToRead1--)
+ {
+ /* Wait until end of transmit */
+ while(SPI_I2S_GetFlagStatus(SPI1, SPI_I2S_FLAG_TXE)== RESET)
+ {
+ }
+ /* Write one byte in the SPI1 Transmit Data Register */
+ SPI_I2S_SendData(SPI1, TxBuffer2[TxCounter2++]);
+
+ /* Send a Dummy byte to generate clock to slave */
+ USART_SendData(USART1, DYMMY_BYTE);
+ /* Wait until end of transmit */
+ while(USART_GetFlagStatus(USART1, USART_FLAG_TC) == RESET)
+ {
+ }
+ /* Wait the byte is entirtly received by USART1 */
+ while(USART_GetFlagStatus(USART1,USART_FLAG_RXNE) == RESET)
+ {
+ }
+ /* Store the received byte in the RxBuffer1 */
+ RxBuffer1[RxCounter1++] = USART_ReceiveData(USART1);
+ }
+
+ /* Check the received data with the send ones */
+ TransferStatus1 = Buffercmp(TxBuffer1, RxBuffer2, TxBufferSize1);
+ /* TransferStatus = PASSED, if the data transmitted from USART1 and
+ received by SPI1 are the same */
+ /* TransferStatus = FAILED, if the data transmitted from USART1 and
+ received by SPI1 are different */
+ TransferStatus2 = Buffercmp(TxBuffer2, RxBuffer1, TxBufferSize2);
+ /* TransferStatus = PASSED, if the data transmitted from SPI1 and
+ received by USART1 are the same */
+ /* TransferStatus = FAILED, if the data transmitted from SPI1 and
+ received by USART1 are different */
+
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if(HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 2 wait state */
+ FLASH_SetLatency(FLASH_Latency_2);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK/2 */
+ RCC_PCLK1Config(RCC_HCLK_Div2);
+
+ /* PLLCLK = 8MHz * 9 = 72 MHz */
+ RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+
+ /* Enable PLL */
+ RCC_PLLCmd(ENABLE);
+
+ /* Wait till PLL is ready */
+ while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET)
+ {
+ }
+
+ /* Select PLL as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+
+ /* Wait till PLL is used as system clock source */
+ while(RCC_GetSYSCLKSource() != 0x08)
+ {
+ }
+ }
+
+ /* Enable SPI1, USART1 and GPIOA clocks */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1 | RCC_APB2Periph_USART1
+ | RCC_APB2Periph_GPIOA, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure USART1 Tx (PA.09) and USART1 CK(PA.08) as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9 | GPIO_Pin_8;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure SPI1 pins: NSS, SCK, MISO and MOSI */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ /* Configure USART1 Rx (PA.10) as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+}
+
+/*******************************************************************************
+* Function Name : SPI_Configuration
+* Description : Configures the SPI.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_Configuration(void)
+{
+ SPI_InitTypeDef SPI_InitStructure;
+
+ SPI_StructInit(&SPI_InitStructure);
+
+ SPI_I2S_DeInit(SPI1);
+
+ /* SPI1 Config */
+ SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
+ SPI_InitStructure.SPI_Mode = SPI_Mode_Slave;
+ SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
+ SPI_InitStructure.SPI_CPOL = SPI_CPOL_High;
+ SPI_InitStructure.SPI_CPHA = SPI_CPHA_2Edge;
+ SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
+ SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_LSB;
+
+ /* Configure SPI1 */
+ SPI_Init(SPI1, &SPI_InitStructure);
+
+ /* SPI1 enable */
+ SPI_Cmd(SPI1, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : Buffercmp
+* Description : Compares two buffers.
+* Input : - pBuffer1, pBuffer2: buffers to be compared.
+* : - BufferLength: buffer's length
+* Output : None
+* Return : PASSED: pBuffer1 identical to pBuffer2
+* FAILED: pBuffer1 differs from pBuffer2
+*******************************************************************************/
+TestStatus Buffercmp(u8* pBuffer1, u8* pBuffer2, u16 BufferLength)
+{
+ while(BufferLength--)
+ {
+ if(*pBuffer1 != *pBuffer2)
+ {
+ return FAILED;
+ }
+
+ pBuffer1++;
+ pBuffer2++;
+ }
+
+ return PASSED;
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Synchronous/readme.txt b/src/stm32lib/examples/USART/Synchronous/readme.txt new file mode 100755 index 0000000..1fb128c --- /dev/null +++ b/src/stm32lib/examples/USART/Synchronous/readme.txt @@ -0,0 +1,88 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the USART Synchronous Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example provides a basic communication between USART1 (Synchronous mode)
+and SPI1 using flags.
+
+First, the USART1 sends data from TxBuffer1 buffer to SPI1 using USART1 TXE flag.
+Data received, using RXNE flag, by SPI1 is stored in RxBuffer2 then compared with
+the sent ones and the result of this comparison is stored in the "TransferStatus1"
+variable.
+
+Then, the SPI1 sends data from TxBuffer2 buffer to USART1 using SPI1 TXE flag.
+Data received, using RXNE flag, by USART1 is stored in RxBuffer1 then compared with
+the sent ones and the result of this comparison is stored in the "TransferStatus2"
+variable.
+
+
+USART1 configured as follow:
+ - BaudRate = 115200 baud
+ - Word Length = 8 Bits
+ - One Stop Bit
+ - No parity
+ - Hardware flow control disabled (RTS and CTS signals)
+ - Receive and transmit enabled
+ - USART Clock enabled
+ - USART CPOL: Clock is active high
+ - USART CPHA: Data is captured on the second edge
+ - USART LastBit: The clock pulse of the last data bit is output to the SCLK pin
+
+SPI1 configured as follow:
+ - Direction = 2 Lines FullDuplex
+ - Mode = Slave Mode
+ - DataSize = 8 Bits
+ - CPOL = Clock is active high
+ - CPHA = Data is captured on the second edge
+ - NSS = NSS Software
+ - First Bit = First Bit is the LSB
+
+
+Directory contents
+==================
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.h Interrupt handlers header file
+stm32f10x_it.c Interrupt handlers
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+There is no need for any modification when switching between these two boards.
+
+Connect USART1_Tx(PA.09) to SPI1_MOSI(PA.07), USART1_Rx(PA.10) to SPI1_MISO(PA.06)
+and USART1_CK(PA.08) to SPI1_SCK(PA.05).
+
+
+How to use it
+=============
+In order to make the program work, you must do the following :
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files :
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_usart.c
+ + stm32f10x_spi.c
+ + stm32f10x_nvic.c
+ + stm32f10x_flash.c
+
+- Link all compiled files and load your image into target memory
+- Run the example
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/USART/Synchronous/stm32f10x_conf.h b/src/stm32lib/examples/USART/Synchronous/stm32f10x_conf.h new file mode 100755 index 0000000..777597f --- /dev/null +++ b/src/stm32lib/examples/USART/Synchronous/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+//#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+#define _GPIOA
+//#define _GPIOB
+//#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+//#define _GPIOF
+//#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+//#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+#define _SPI
+#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+#define _USART
+#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+//#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Synchronous/stm32f10x_it.c b/src/stm32lib/examples/USART/Synchronous/stm32f10x_it.c new file mode 100755 index 0000000..e27c1e7 --- /dev/null +++ b/src/stm32lib/examples/USART/Synchronous/stm32f10x_it.c @@ -0,0 +1,810 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{
+}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/USART/Synchronous/stm32f10x_it.h b/src/stm32lib/examples/USART/Synchronous/stm32f10x_it.h new file mode 100755 index 0000000..e74b6cc --- /dev/null +++ b/src/stm32lib/examples/USART/Synchronous/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/WWDG/main.c b/src/stm32lib/examples/WWDG/main.c new file mode 100755 index 0000000..a59b45e --- /dev/null +++ b/src/stm32lib/examples/WWDG/main.c @@ -0,0 +1,257 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : main.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main program body.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+#include "platform_config.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+ErrorStatus HSEStartUpStatus;
+
+/* Private function prototypes -----------------------------------------------*/
+void RCC_Configuration(void);
+void NVIC_Configuration(void);
+void GPIO_Configuration(void);
+void EXTI_Configuration(void);
+void Delay(vu32 nCount);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : main
+* Description : Main program.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+int main(void)
+{
+#ifdef DEBUG
+ debug();
+#endif
+
+ /* System Clocks Configuration */
+ RCC_Configuration();
+
+ /* GPIO configuration */
+ GPIO_Configuration();
+
+ /* Check if the system has resumed from WWDG reset */
+ if (RCC_GetFlagStatus(RCC_FLAG_WWDGRST) != RESET)
+ { /* WWDGRST flag set */
+ /* Set GPIO_LED pin 6 */
+ GPIO_SetBits(GPIO_LED, GPIO_Pin_6);
+
+ /* Clear reset flags */
+ RCC_ClearFlag();
+ }
+ else
+ { /* WWDGRST flag is not set */
+ /* Reset GPIO_LED pin 6 */
+ GPIO_ResetBits(GPIO_LED, GPIO_Pin_6);
+ }
+
+ /* Configure Key Button EXTI Line to generate an interrupt on falling edge */
+ EXTI_Configuration();
+
+ /* NVIC configuration */
+ NVIC_Configuration();
+
+ /* WWDG configuration */
+ /* Enable WWDG clock */
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_WWDG, ENABLE);
+
+ /* WWDG clock counter = (PCLK1/4096)/8 = 244 Hz (~4 ms) */
+ WWDG_SetPrescaler(WWDG_Prescaler_8);
+
+ /* Set Window value to 65 */
+ WWDG_SetWindowValue(65);
+
+ /* Enable WWDG and set counter value to 127, WWDG timeout = ~4 ms * 64 = 262 ms */
+ WWDG_Enable(127);
+
+ /* Clear EWI flag */
+ WWDG_ClearFlag();
+
+ /* Enable EW interrupt */
+ WWDG_EnableIT();
+
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : RCC_Configuration
+* Description : Configures the different system clocks.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_Configuration(void)
+{
+ /* RCC system reset(for debug purpose) */
+ RCC_DeInit();
+
+ /* Enable HSE */
+ RCC_HSEConfig(RCC_HSE_ON);
+
+ /* Wait till HSE is ready */
+ HSEStartUpStatus = RCC_WaitForHSEStartUp();
+
+ if (HSEStartUpStatus == SUCCESS)
+ {
+ /* Enable Prefetch Buffer */
+ FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+
+ /* Flash 0 wait state */
+ FLASH_SetLatency(FLASH_Latency_0);
+
+ /* HCLK = SYSCLK */
+ RCC_HCLKConfig(RCC_SYSCLK_Div1);
+
+ /* PCLK2 = HCLK */
+ RCC_PCLK2Config(RCC_HCLK_Div1);
+
+ /* PCLK1 = HCLK */
+ RCC_PCLK1Config(RCC_HCLK_Div1);
+
+ /* Select HSE as system clock source */
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_HSE);
+
+ /* Wait till HSE is used as system clock source */
+ while (RCC_GetSYSCLKSource() != 0x04)
+ {}
+ }
+
+ /* Enable Key Button GPIO Port, GPIO_LED and AFIO clock */
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIO_KEY_BUTTON | RCC_APB2Periph_GPIO_LED
+ | RCC_APB2Periph_AFIO, ENABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Configuration
+* Description : Configures the different GPIO ports.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Configuration(void)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ /* Configure GPIO_LED pin 6 and pin 7 as Output push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+ GPIO_Init(GPIO_LED, &GPIO_InitStructure);
+
+ /* Configure Key Button GPIO Pin as input floating */
+ GPIO_InitStructure.GPIO_Pin = GPIO_PIN_KEY_BUTTON;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+ GPIO_Init(GPIO_KEY_BUTTON, & GPIO_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : EXTI_Configuration
+* Description : Configures EXTI Line9.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_Configuration(void)
+{
+ EXTI_InitTypeDef EXTI_InitStructure;
+
+ /* Connect Key Button EXTI Line to Key Button GPIO Pin */
+ GPIO_EXTILineConfig(GPIO_PORT_SOURCE_KEY_BUTTON, GPIO_PIN_SOURCE_KEY_BUTTON);
+
+ /* Configure Key Button EXTI Line to generate an interrupt on falling edge */
+ EXTI_ClearITPendingBit(EXTI_LINE_KEY_BUTTON);
+ EXTI_InitStructure.EXTI_Line = EXTI_LINE_KEY_BUTTON;
+ EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
+ EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
+ EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+ EXTI_Init(&EXTI_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Configuration
+* Description : Configures NVIC and Vector Table base location.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Configuration(void)
+{
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+#ifdef VECT_TAB_RAM
+ /* Set the Vector Table base location at 0x20000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0);
+#else /* VECT_TAB_FLASH */
+ /* Set the Vector Table base location at 0x08000000 */
+ NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+#endif
+
+ /* 2 bits for Preemption Priority and 2 bits for Sub Priority */
+ NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
+
+ NVIC_InitStructure.NVIC_IRQChannel = EXTI9_5_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ NVIC_InitStructure.NVIC_IRQChannel = WWDG_IRQChannel;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;
+ NVIC_Init(&NVIC_InitStructure);
+}
+
+/*******************************************************************************
+* Function Name : Delay
+* Description : Inserts a delay time.
+* Input : nCount: specifies the delay time length.
+* Output : None
+* Return : None
+*******************************************************************************/
+void Delay(vu32 nCount)
+{
+ for (; nCount != 0; nCount--);
+}
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : assert_failed
+* Description : Reports the name of the source file and the source line number
+* where the assert_param error has occurred.
+* Input : - file: pointer to the source file name
+* - line: assert_param error line source number
+* Output : None
+* Return : None
+*******************************************************************************/
+void assert_failed(u8* file, u32 line)
+{
+ /* User can add his own implementation to report the file name and line number,
+ ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+
+ /* Infinite loop */
+ while (1)
+ {}
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/WWDG/platform_config.h b/src/stm32lib/examples/WWDG/platform_config.h new file mode 100755 index 0000000..4d96ed9 --- /dev/null +++ b/src/stm32lib/examples/WWDG/platform_config.h @@ -0,0 +1,56 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : platform_config.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Evaluation board specific configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __PLATFORM_CONFIG_H
+#define __PLATFORM_CONFIG_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line corresponding to the STMicroelectronics evaluation board
+ used to run the example */
+#if !defined (USE_STM3210B_EVAL) && !defined (USE_STM3210E_EVAL)
+//#define USE_STM3210B_EVAL
+#define USE_STM3210E_EVAL
+#endif
+
+/* Define the STM32F10x hardware depending on the used evaluation board */
+#ifdef USE_STM3210B_EVAL
+ #define GPIO_LED GPIOC
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOC
+ #define GPIO_KEY_BUTTON GPIOB
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOB
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_9
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line9
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOB
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource9
+#elif defined USE_STM3210E_EVAL
+ #define GPIO_LED GPIOF
+ #define RCC_APB2Periph_GPIO_LED RCC_APB2Periph_GPIOF
+ #define GPIO_KEY_BUTTON GPIOG
+ #define RCC_APB2Periph_GPIO_KEY_BUTTON RCC_APB2Periph_GPIOG
+ #define GPIO_PIN_KEY_BUTTON GPIO_Pin_8
+ #define EXTI_LINE_KEY_BUTTON EXTI_Line8
+ #define GPIO_PORT_SOURCE_KEY_BUTTON GPIO_PortSourceGPIOG
+ #define GPIO_PIN_SOURCE_KEY_BUTTON GPIO_PinSource8
+#endif /* USE_STM3210B_EVAL */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __PLATFORM_CONFIG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/WWDG/readme.txt b/src/stm32lib/examples/WWDG/readme.txt new file mode 100755 index 0000000..0314137 --- /dev/null +++ b/src/stm32lib/examples/WWDG/readme.txt @@ -0,0 +1,87 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : readme.txt
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Description of the WWDG Example.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+Example description
+===================
+This example shows how to update at regulate period the WWDG counter using the
+Early Wakeup interrupt (EWI).
+
+The WWDG timeout is set to 262 ms, the refresh window is set to 65 and the EWI is
+enabled. When the WWDG counter reaches 64, the EWI is generated. In the WWDG ISR,
+the counter is refreshed to prevent a WWDG reset and a specific GPIO pin is toggled.
+
+An EXTI Line is connected to a GPIO pin, and configured to generate an interrupt
+on the falling edge of the signal.
+In the NVIC (nested vectored interrupt controller), the EXTI Line interrupt
+vector is enabled with a priority equal to 0 and the WWDG interrupt vector is
+enabled with a priority equal to 1 (EXTI IT > WWDG IT).
+
+The EXTI Line is used to simulate a software failure: once the EXTI Line event occurs
+(by pressing the Key push-button on the STM3210B-EVAL board), the corresponding
+interrupt is served. In the ISR, the GPIO pin is reset and the EXTI Line pending
+bit is not cleared. So the CPU executes the EXTI Line ISR indefinitely and the
+WWDG ISR is never executed (the WWDG counter is not updated).
+As a result, when the WWDG counter falls to 63, the WWDG reset occurs.
+If the WWDG reset is generated, after the system resumes from reset, an other GPIO
+is set.
+
+If the EXTI Line event does not occur, the WWDG counter is indefinitely refreshed
+in the WWDG ISR, and there is no WWDG reset.
+
+In this example the system is clocked by HSE, the high-speed external clock (8 MHz).
+
+
+Directory contents
+==================
+platform_config.h Evaluation board specific configuration file
+stm32f10x_conf.h Library Configuration file
+stm32f10x_it.c Interrupt handlers
+stm32f10x_it.h Header for stm32f10x_it.c
+main.c Main program
+
+
+Hardware environment
+====================
+This example runs on STMicroelectronics STM3210B-EVAL and STM3210E-EVAL evaluation
+boards and can be easily tailored to any other hardware.
+To select the STMicroelectronics evaluation board used to run the example, uncomment
+the corresponding line in platform_config.h file.
+
+ + STM3210B-EVAL
+ - Use LD1 and LD2 leds connected respectively to PC.06 and PC.07 pins, and the
+ KEY push button connected to PB.09 pin.
+
+ + STM3210E-EVAL
+ - Use LD1 and LD2 leds connected respectively to PF.06 and PF.07 pins, and the
+ KEY push button connected to PG.08 pin.
+
+
+How to use it
+=============
+In order to make the program work, you must do the following:
+- Create a project and setup all your toolchain's start-up files
+- Compile the directory content files and required Library files:
+ + stm32f10x_lib.c
+ + stm32f10x_gpio.c
+ + stm32f10x_rcc.c
+ + stm32f10x_nvic.c
+ + stm32f10x_wwdg.c
+ + stm32f10x_flash.c
+ + stm32f10x_exti.c
+
+- Link all compiled files and load your image into target memory
+- Run the example in standalone mode (without debugger connection)
+
+******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE******
diff --git a/src/stm32lib/examples/WWDG/stm32f10x_conf.h b/src/stm32lib/examples/WWDG/stm32f10x_conf.h new file mode 100755 index 0000000..892bcc6 --- /dev/null +++ b/src/stm32lib/examples/WWDG/stm32f10x_conf.h @@ -0,0 +1,170 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_conf.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Library configuration file.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
+ the "assert_param" macro in the firmware library code (see "Exported macro"
+ section below) */
+/*#define DEBUG 1*/
+
+/* Comment the line below to disable the specific peripheral inclusion */
+/************************************* ADC ************************************/
+//#define _ADC
+//#define _ADC1
+//#define _ADC2
+//#define _ADC3
+
+/************************************* BKP ************************************/
+//#define _BKP
+
+/************************************* CAN ************************************/
+//#define _CAN
+
+/************************************* CRC ************************************/
+//#define _CRC
+
+/************************************* DAC ************************************/
+//#define _DAC
+
+/************************************* DBGMCU *********************************/
+//#define _DBGMCU
+
+/************************************* DMA ************************************/
+//#define _DMA
+//#define _DMA1_Channel1
+//#define _DMA1_Channel2
+//#define _DMA1_Channel3
+//#define _DMA1_Channel4
+//#define _DMA1_Channel5
+//#define _DMA1_Channel6
+//#define _DMA1_Channel7
+//#define _DMA2_Channel1
+//#define _DMA2_Channel2
+//#define _DMA2_Channel3
+//#define _DMA2_Channel4
+//#define _DMA2_Channel5
+
+/************************************* EXTI ***********************************/
+#define _EXTI
+
+/************************************* FLASH and Option Bytes *****************/
+#define _FLASH
+/* Uncomment the line below to enable FLASH program/erase/protections functions,
+ otherwise only FLASH configuration (latency, prefetch, half cycle) functions
+ are enabled */
+/* #define _FLASH_PROG */
+
+/************************************* FSMC ***********************************/
+//#define _FSMC
+
+/************************************* GPIO ***********************************/
+#define _GPIO
+//#define _GPIOA
+#define _GPIOB
+#define _GPIOC
+//#define _GPIOD
+//#define _GPIOE
+#define _GPIOF
+#define _GPIOG
+#define _AFIO
+
+/************************************* I2C ************************************/
+//#define _I2C
+//#define _I2C1
+//#define _I2C2
+
+/************************************* IWDG ***********************************/
+//#define _IWDG
+
+/************************************* NVIC ***********************************/
+#define _NVIC
+
+/************************************* PWR ************************************/
+#define _PWR
+
+/************************************* RCC ************************************/
+#define _RCC
+
+/************************************* RTC ************************************/
+//#define _RTC
+
+/************************************* SDIO ***********************************/
+//#define _SDIO
+
+/************************************* SPI ************************************/
+//#define _SPI
+//#define _SPI1
+//#define _SPI2
+//#define _SPI3
+
+/************************************* SysTick ********************************/
+//#define _SysTick
+
+/************************************* TIM ************************************/
+//#define _TIM
+//#define _TIM1
+//#define _TIM2
+//#define _TIM3
+//#define _TIM4
+//#define _TIM5
+//#define _TIM6
+//#define _TIM7
+//#define _TIM8
+
+/************************************* USART **********************************/
+//#define _USART
+//#define _USART1
+//#define _USART2
+//#define _USART3
+//#define _UART4
+//#define _UART5
+
+/************************************* WWDG ***********************************/
+#define _WWDG
+
+/* In the following line adjust the value of External High Speed oscillator (HSE)
+ used in your application */
+#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef DEBUG
+/*******************************************************************************
+* Macro Name : assert_param
+* Description : The assert_param macro is used for function's parameters check.
+* It is used only if the library is compiled in DEBUG mode.
+* Input : - expr: If expr is false, it calls assert_failed function
+* which reports the name of the source file and the source
+* line number of the call that failed.
+* If expr is true, it returns no value.
+* Return : None
+*******************************************************************************/
+#define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(u8* file, u32 line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* DEBUG */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/WWDG/stm32f10x_it.c b/src/stm32lib/examples/WWDG/stm32f10x_it.c new file mode 100755 index 0000000..6184eb5 --- /dev/null +++ b/src/stm32lib/examples/WWDG/stm32f10x_it.c @@ -0,0 +1,762 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.c
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : Main Interrupt Service Routines.
+* This file provides template for all exceptions handler
+* and peripherals interrupt service routine.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_it.h"
+#include "platform_config.h"
+
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NMIException
+* Description : This function handles NMI exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NMIException(void)
+{}
+
+/*******************************************************************************
+* Function Name : HardFaultException
+* Description : This function handles Hard Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void HardFaultException(void)
+{
+ /* Go to infinite loop when Hard Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : MemManageException
+* Description : This function handles Memory Manage exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void MemManageException(void)
+{
+ /* Go to infinite loop when Memory Manage exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : BusFaultException
+* Description : This function handles Bus Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BusFaultException(void)
+{
+ /* Go to infinite loop when Bus Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : UsageFaultException
+* Description : This function handles Usage Fault exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UsageFaultException(void)
+{
+ /* Go to infinite loop when Usage Fault exception occurs */
+ while (1)
+ {}
+}
+
+/*******************************************************************************
+* Function Name : DebugMonitor
+* Description : This function handles Debug Monitor exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DebugMonitor(void)
+{}
+
+/*******************************************************************************
+* Function Name : SVCHandler
+* Description : This function handles SVCall exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SVCHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : PendSVC
+* Description : This function handles PendSVC exception.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PendSVC(void)
+{}
+
+/*******************************************************************************
+* Function Name : SysTickHandler
+* Description : This function handles SysTick Handler.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTickHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : WWDG_IRQHandler
+* Description : This function handles WWDG interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_IRQHandler(void)
+{
+ /* Update WWDG counter */
+ WWDG_SetCounter(0x7F);
+
+ /* Clear EWI flag */
+ WWDG_ClearFlag();
+
+ /* Toggle GPIO_Led pin 7 */
+ GPIO_WriteBit(GPIO_LED, GPIO_Pin_7, (BitAction)(1 - GPIO_ReadOutputDataBit(GPIO_LED, GPIO_Pin_7)));
+}
+
+/*******************************************************************************
+* Function Name : PVD_IRQHandler
+* Description : This function handles PVD interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PVD_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TAMPER_IRQHandler
+* Description : This function handles Tamper interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TAMPER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTC_IRQHandler
+* Description : This function handles RTC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FLASH_IRQHandler
+* Description : This function handles Flash interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RCC_IRQHandler
+* Description : This function handles RCC interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI0_IRQHandler
+* Description : This function handles External interrupt Line 0 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI1_IRQHandler
+* Description : This function handles External interrupt Line 1 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI2_IRQHandler
+* Description : This function handles External interrupt Line 2 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI3_IRQHandler
+* Description : This function handles External interrupt Line 3 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI4_IRQHandler
+* Description : This function handles External interrupt Line 4 request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel1_IRQHandler
+* Description : This function handles DMA1 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel2_IRQHandler
+* Description : This function handles DMA1 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel3_IRQHandler
+* Description : This function handles DMA1 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel4_IRQHandler
+* Description : This function handles DMA1 Channel 4 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel5_IRQHandler
+* Description : This function handles DMA1 Channel 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel6_IRQHandler
+* Description : This function handles DMA1 Channel 6 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA1_Channel7_IRQHandler
+* Description : This function handles DMA1 Channel 7 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA1_Channel7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC1_2_IRQHandler
+* Description : This function handles ADC1 and ADC2 global interrupts requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC1_2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_HP_CAN_TX_IRQHandler
+* Description : This function handles USB High Priority or CAN TX interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_HP_CAN_TX_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USB_LP_CAN_RX0_IRQHandler
+* Description : This function handles USB Low Priority or CAN RX0 interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USB_LP_CAN_RX0_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_RX1_IRQHandler
+* Description : This function handles CAN RX1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_RX1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : CAN_SCE_IRQHandler
+* Description : This function handles CAN SCE interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CAN_SCE_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI9_5_IRQHandler
+* Description : This function handles External lines 9 to 5 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI9_5_IRQHandler(void)
+{
+ if (EXTI_GetITStatus(EXTI_LINE_KEY_BUTTON) != RESET)
+ {
+ /* Reset GPIO_Led pin 7 */
+ GPIO_ResetBits(GPIO_LED, GPIO_Pin_7);
+
+ /* As EXTI_LINE_KEY_BUTTON pending bit is not cleared, the CPU will execute
+ indefinitely this ISR and when the WWDG counter falls to 3Fh the WWDG reset
+ occurs */
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM1_BRK_IRQHandler
+* Description : This function handles TIM1 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_UP_IRQHandler
+* Description : This function handles TIM1 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_TRG_COM_IRQHandler
+* Description : This function handles TIM1 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM1_CC_IRQHandler
+* Description : This function handles TIM1 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM1_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM2_IRQHandler
+* Description : This function handles TIM2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM3_IRQHandler
+* Description : This function handles TIM3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM4_IRQHandler
+* Description : This function handles TIM4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_EV_IRQHandler
+* Description : This function handles I2C1 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C1_ER_IRQHandler
+* Description : This function handles I2C1 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C1_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_EV_IRQHandler
+* Description : This function handles I2C2 Event interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_EV_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : I2C2_ER_IRQHandler
+* Description : This function handles I2C2 Error interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C2_ER_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI1_IRQHandler
+* Description : This function handles SPI1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI2_IRQHandler
+* Description : This function handles SPI2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART1_IRQHandler
+* Description : This function handles USART1 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART2_IRQHandler
+* Description : This function handles USART2 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USART3_IRQHandler
+* Description : This function handles USART3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : EXTI15_10_IRQHandler
+* Description : This function handles External lines 15 to 10 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI15_10_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : RTCAlarm_IRQHandler
+* Description : This function handles RTC Alarm interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTCAlarm_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : USBWakeUp_IRQHandler
+* Description : This function handles USB WakeUp interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void USBWakeUp_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_BRK_IRQHandler
+* Description : This function handles TIM8 Break interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_BRK_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_UP_IRQHandler
+* Description : This function handles TIM8 overflow and update interrupt
+* request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_UP_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_TRG_COM_IRQHandler
+* Description : This function handles TIM8 Trigger and commutation interrupts
+* requests.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_TRG_COM_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM8_CC_IRQHandler
+* Description : This function handles TIM8 capture compare interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM8_CC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : ADC3_IRQHandler
+* Description : This function handles ADC3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : FSMC_IRQHandler
+* Description : This function handles FSMC global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SDIO_IRQHandler
+* Description : This function handles SDIO global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM5_IRQHandler
+* Description : This function handles TIM5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : SPI3_IRQHandler
+* Description : This function handles SPI3 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART4_IRQHandler
+* Description : This function handles UART4 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART4_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : UART5_IRQHandler
+* Description : This function handles UART5 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void UART5_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM6_IRQHandler
+* Description : This function handles TIM6 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM6_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : TIM7_IRQHandler
+* Description : This function handles TIM7 global interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM7_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel1_IRQHandler
+* Description : This function handles DMA2 Channel 1 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel1_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel2_IRQHandler
+* Description : This function handles DMA2 Channel 2 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel2_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel3_IRQHandler
+* Description : This function handles DMA2 Channel 3 interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel3_IRQHandler(void)
+{}
+
+/*******************************************************************************
+* Function Name : DMA2_Channel4_5_IRQHandler
+* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5
+* interrupt request.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA2_Channel4_5_IRQHandler(void)
+{}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/examples/WWDG/stm32f10x_it.h b/src/stm32lib/examples/WWDG/stm32f10x_it.h new file mode 100755 index 0000000..58da1cc --- /dev/null +++ b/src/stm32lib/examples/WWDG/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_it.h
+* Author : MCD Application Team
+* Version : V2.0.1
+* Date : 06/13/2008
+* Description : This file contains the headers of the interrupt handlers.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IT_H
+#define __STM32F10x_IT_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void NMIException(void);
+void HardFaultException(void);
+void MemManageException(void);
+void BusFaultException(void);
+void UsageFaultException(void);
+void DebugMonitor(void);
+void SVCHandler(void);
+void PendSVC(void);
+void SysTickHandler(void);
+void WWDG_IRQHandler(void);
+void PVD_IRQHandler(void);
+void TAMPER_IRQHandler(void);
+void RTC_IRQHandler(void);
+void FLASH_IRQHandler(void);
+void RCC_IRQHandler(void);
+void EXTI0_IRQHandler(void);
+void EXTI1_IRQHandler(void);
+void EXTI2_IRQHandler(void);
+void EXTI3_IRQHandler(void);
+void EXTI4_IRQHandler(void);
+void DMA1_Channel1_IRQHandler(void);
+void DMA1_Channel2_IRQHandler(void);
+void DMA1_Channel3_IRQHandler(void);
+void DMA1_Channel4_IRQHandler(void);
+void DMA1_Channel5_IRQHandler(void);
+void DMA1_Channel6_IRQHandler(void);
+void DMA1_Channel7_IRQHandler(void);
+void ADC1_2_IRQHandler(void);
+void USB_HP_CAN_TX_IRQHandler(void);
+void USB_LP_CAN_RX0_IRQHandler(void);
+void CAN_RX1_IRQHandler(void);
+void CAN_SCE_IRQHandler(void);
+void EXTI9_5_IRQHandler(void);
+void TIM1_BRK_IRQHandler(void);
+void TIM1_UP_IRQHandler(void);
+void TIM1_TRG_COM_IRQHandler(void);
+void TIM1_CC_IRQHandler(void);
+void TIM2_IRQHandler(void);
+void TIM3_IRQHandler(void);
+void TIM4_IRQHandler(void);
+void I2C1_EV_IRQHandler(void);
+void I2C1_ER_IRQHandler(void);
+void I2C2_EV_IRQHandler(void);
+void I2C2_ER_IRQHandler(void);
+void SPI1_IRQHandler(void);
+void SPI2_IRQHandler(void);
+void USART1_IRQHandler(void);
+void USART2_IRQHandler(void);
+void USART3_IRQHandler(void);
+void EXTI15_10_IRQHandler(void);
+void RTCAlarm_IRQHandler(void);
+void USBWakeUp_IRQHandler(void);
+void TIM8_BRK_IRQHandler(void);
+void TIM8_UP_IRQHandler(void);
+void TIM8_TRG_COM_IRQHandler(void);
+void TIM8_CC_IRQHandler(void);
+void ADC3_IRQHandler(void);
+void FSMC_IRQHandler(void);
+void SDIO_IRQHandler(void);
+void TIM5_IRQHandler(void);
+void SPI3_IRQHandler(void);
+void UART4_IRQHandler(void);
+void UART5_IRQHandler(void);
+void TIM6_IRQHandler(void);
+void TIM7_IRQHandler(void);
+void DMA2_Channel1_IRQHandler(void);
+void DMA2_Channel2_IRQHandler(void);
+void DMA2_Channel3_IRQHandler(void);
+void DMA2_Channel4_5_IRQHandler(void);
+
+#endif /* __STM32F10x_IT_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/cortexm3_macro.h b/src/stm32lib/inc/cortexm3_macro.h new file mode 100644 index 0000000..26b04ef --- /dev/null +++ b/src/stm32lib/inc/cortexm3_macro.h @@ -0,0 +1,176 @@ +#if 0
+/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : cortexm3_macro.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : Header file for cortexm3_macro.s.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __CORTEXM3_MACRO_H
+#define __CORTEXM3_MACRO_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void __WFI(void);
+void __WFE(void);
+void __SEV(void);
+void __ISB(void);
+void __DSB(void);
+void __DMB(void);
+void __SVC(void);
+u32 __MRS_CONTROL(void);
+void __MSR_CONTROL(u32 Control);
+u32 __MRS_PSP(void);
+void __MSR_PSP(u32 TopOfProcessStack);
+u32 __MRS_MSP(void);
+void __MSR_MSP(u32 TopOfMainStack);
+void __RESETPRIMASK(void);
+void __SETPRIMASK(void);
+u32 __READ_PRIMASK(void);
+void __RESETFAULTMASK(void);
+void __SETFAULTMASK(void);
+u32 __READ_FAULTMASK(void);
+void __BASEPRICONFIG(u32 NewPriority);
+u32 __GetBASEPRI(void);
+u16 __REV_HalfWord(u16 Data);
+u32 __REV_Word(u32 Data);
+
+#endif /* __CORTEXM3_MACRO_H */
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
+
+/******************** (C) COPYRIGHT 2008 Andreas Fritiofson ********************
+* File Name : cortexm3_macro.h
+* Author : Andreas Fritiofson
+* Version : V1.0
+* Date : 30/04/2008
+* Description : Instruction wrappers for special Cortex-M3 instructions.
+********************************************************************************
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __CORTEXM3_MACRO_H
+#define __CORTEXM3_MACRO_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_type.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+static inline void __WFI(void) {
+ asm volatile ( "WFI \n" );
+}
+static inline void __WFE(void) {
+ asm volatile ( "WFE \n" );
+}
+static inline void __SEV(void) {
+ asm volatile ( "SEV \n" );
+}
+static inline void __ISB(void) {
+ asm volatile ( "ISB \n" );
+}
+static inline void __DSB(void) {
+ asm volatile ( "DSB \n" );
+}
+static inline void __DMB(void) {
+ asm volatile ( "DMB \n" );
+}
+static inline void __SVC(void) {
+ asm volatile ( "SVC 0x01 \n" );
+}
+static inline u32 __MRS_CONTROL(void) {
+ u32 x;
+ asm volatile ( "MRS %0, control \n" : "=r" (x));
+ return x;
+}
+static inline void __MSR_CONTROL(u32 Control) {
+ asm volatile (
+ "MSR control, %0 \n"
+ "ISB \n"
+ : : "r" (Control));
+}
+static inline u32 __MRS_PSP(void) {
+ u32 x;
+ asm volatile ( "MRS %0, psp \n" : "=r" (x));
+ return x;
+}
+static inline void __MSR_PSP(u32 TopOfProcessStack) {
+ asm volatile ( "MSR psp, %0 \n" : : "r" (TopOfProcessStack));
+}
+static inline u32 __MRS_MSP(void) {
+ u32 x;
+ asm volatile ( "MRS %0, msp \n" : "=r" (x));
+ return x;
+}
+static inline void __MSR_MSP(u32 TopOfMainStack) {
+ asm volatile ( "MSR msp, %0 \n" : : "r" (TopOfMainStack));
+}
+static inline void __SETPRIMASK(void) {
+ asm volatile ( "CPSID i \n" );
+}
+static inline void __RESETPRIMASK(void) {
+ asm volatile ( "CPSIE i \n" );
+}
+static inline void __SETFAULTMASK(void) {
+ asm volatile ( "CPSID f \n" );
+}
+static inline void __RESETFAULTMASK(void) {
+ asm volatile ( "CPSIE f \n" );
+}
+static inline void __BASEPRICONFIG(u32 NewPriority) {
+ asm volatile ( "MSR basepri, %0 \n" : : "r" (NewPriority));
+}
+static inline u32 __GetBASEPRI(void) {
+ u32 x;
+ asm volatile ( "MRS %0, basepri_max \n" : "=r" (x));
+ return x;
+}
+static inline u16 __REV_HalfWord(u16 Data) {
+ u16 x;
+ asm volatile ( "REV16 %0, %1 \n" : "=r" (x) : "r" (Data));
+ return x;
+}
+static inline u32 __REV_Word(u32 Data) {
+ u32 x;
+ asm volatile ( "REV %0, %1 \n" : "=r" (x) : "r" (Data));
+ return x;
+}
+
+#endif /* __CORTEXM3_MACRO_H */
+
+/******************* (C) COPYRIGHT 2008 Andreas Fritiofson *****END OF FILE****/
+
diff --git a/src/stm32lib/inc/stm32f10x_adc.h b/src/stm32lib/inc/stm32f10x_adc.h new file mode 100644 index 0000000..8fc9098 --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_adc.h @@ -0,0 +1,300 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_adc.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* ADC firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_ADC_H
+#define __STM32F10x_ADC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* ADC Init structure definition */
+typedef struct
+{
+ u32 ADC_Mode;
+ FunctionalState ADC_ScanConvMode;
+ FunctionalState ADC_ContinuousConvMode;
+ u32 ADC_ExternalTrigConv;
+ u32 ADC_DataAlign;
+ u8 ADC_NbrOfChannel;
+}ADC_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+#define IS_ADC_ALL_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == ADC1_BASE) || \
+ ((*(u32*)&(PERIPH)) == ADC2_BASE) || \
+ ((*(u32*)&(PERIPH)) == ADC3_BASE))
+
+#define IS_ADC_DMA_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == ADC1_BASE) || \
+ ((*(u32*)&(PERIPH)) == ADC3_BASE))
+
+/* ADC dual mode -------------------------------------------------------------*/
+#define ADC_Mode_Independent ((u32)0x00000000)
+#define ADC_Mode_RegInjecSimult ((u32)0x00010000)
+#define ADC_Mode_RegSimult_AlterTrig ((u32)0x00020000)
+#define ADC_Mode_InjecSimult_FastInterl ((u32)0x00030000)
+#define ADC_Mode_InjecSimult_SlowInterl ((u32)0x00040000)
+#define ADC_Mode_InjecSimult ((u32)0x00050000)
+#define ADC_Mode_RegSimult ((u32)0x00060000)
+#define ADC_Mode_FastInterl ((u32)0x00070000)
+#define ADC_Mode_SlowInterl ((u32)0x00080000)
+#define ADC_Mode_AlterTrig ((u32)0x00090000)
+
+#define IS_ADC_MODE(MODE) (((MODE) == ADC_Mode_Independent) || \
+ ((MODE) == ADC_Mode_RegInjecSimult) || \
+ ((MODE) == ADC_Mode_RegSimult_AlterTrig) || \
+ ((MODE) == ADC_Mode_InjecSimult_FastInterl) || \
+ ((MODE) == ADC_Mode_InjecSimult_SlowInterl) || \
+ ((MODE) == ADC_Mode_InjecSimult) || \
+ ((MODE) == ADC_Mode_RegSimult) || \
+ ((MODE) == ADC_Mode_FastInterl) || \
+ ((MODE) == ADC_Mode_SlowInterl) || \
+ ((MODE) == ADC_Mode_AlterTrig))
+
+/* ADC extrenal trigger sources for regular channels conversion --------------*/
+/* for ADC1 and ADC2 */
+#define ADC_ExternalTrigConv_T1_CC1 ((u32)0x00000000)
+#define ADC_ExternalTrigConv_T1_CC2 ((u32)0x00020000)
+#define ADC_ExternalTrigConv_T2_CC2 ((u32)0x00060000)
+#define ADC_ExternalTrigConv_T3_TRGO ((u32)0x00080000)
+#define ADC_ExternalTrigConv_T4_CC4 ((u32)0x000A0000)
+#define ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO ((u32)0x000C0000)
+/* for ADC1, ADC2 and ADC3 */
+#define ADC_ExternalTrigConv_T1_CC3 ((u32)0x00040000)
+#define ADC_ExternalTrigConv_None ((u32)0x000E0000)
+/* for ADC3 */
+#define ADC_ExternalTrigConv_T3_CC1 ((u32)0x00000000)
+#define ADC_ExternalTrigConv_T2_CC3 ((u32)0x00020000)
+#define ADC_ExternalTrigConv_T8_CC1 ((u32)0x00060000)
+#define ADC_ExternalTrigConv_T8_TRGO ((u32)0x00080000)
+#define ADC_ExternalTrigConv_T5_CC1 ((u32)0x000A0000)
+#define ADC_ExternalTrigConv_T5_CC3 ((u32)0x000C0000)
+
+#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_ExternalTrigConv_T1_CC1) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T1_CC2) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T1_CC3) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T2_CC2) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T3_TRGO) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T4_CC4) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_None) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T3_CC1) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T2_CC3) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T8_CC1) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T8_TRGO) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T5_CC1) || \
+ ((REGTRIG) == ADC_ExternalTrigConv_T5_CC3))
+
+/* ADC data align ------------------------------------------------------------*/
+#define ADC_DataAlign_Right ((u32)0x00000000)
+#define ADC_DataAlign_Left ((u32)0x00000800)
+
+#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DataAlign_Right) || \
+ ((ALIGN) == ADC_DataAlign_Left))
+
+/* ADC channels --------------------------------------------------------------*/
+#define ADC_Channel_0 ((u8)0x00)
+#define ADC_Channel_1 ((u8)0x01)
+#define ADC_Channel_2 ((u8)0x02)
+#define ADC_Channel_3 ((u8)0x03)
+#define ADC_Channel_4 ((u8)0x04)
+#define ADC_Channel_5 ((u8)0x05)
+#define ADC_Channel_6 ((u8)0x06)
+#define ADC_Channel_7 ((u8)0x07)
+#define ADC_Channel_8 ((u8)0x08)
+#define ADC_Channel_9 ((u8)0x09)
+#define ADC_Channel_10 ((u8)0x0A)
+#define ADC_Channel_11 ((u8)0x0B)
+#define ADC_Channel_12 ((u8)0x0C)
+#define ADC_Channel_13 ((u8)0x0D)
+#define ADC_Channel_14 ((u8)0x0E)
+#define ADC_Channel_15 ((u8)0x0F)
+#define ADC_Channel_16 ((u8)0x10)
+#define ADC_Channel_17 ((u8)0x11)
+
+#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) == ADC_Channel_0) || ((CHANNEL) == ADC_Channel_1) || \
+ ((CHANNEL) == ADC_Channel_2) || ((CHANNEL) == ADC_Channel_3) || \
+ ((CHANNEL) == ADC_Channel_4) || ((CHANNEL) == ADC_Channel_5) || \
+ ((CHANNEL) == ADC_Channel_6) || ((CHANNEL) == ADC_Channel_7) || \
+ ((CHANNEL) == ADC_Channel_8) || ((CHANNEL) == ADC_Channel_9) || \
+ ((CHANNEL) == ADC_Channel_10) || ((CHANNEL) == ADC_Channel_11) || \
+ ((CHANNEL) == ADC_Channel_12) || ((CHANNEL) == ADC_Channel_13) || \
+ ((CHANNEL) == ADC_Channel_14) || ((CHANNEL) == ADC_Channel_15) || \
+ ((CHANNEL) == ADC_Channel_16) || ((CHANNEL) == ADC_Channel_17))
+
+/* ADC sampling times --------------------------------------------------------*/
+#define ADC_SampleTime_1Cycles5 ((u8)0x00)
+#define ADC_SampleTime_7Cycles5 ((u8)0x01)
+#define ADC_SampleTime_13Cycles5 ((u8)0x02)
+#define ADC_SampleTime_28Cycles5 ((u8)0x03)
+#define ADC_SampleTime_41Cycles5 ((u8)0x04)
+#define ADC_SampleTime_55Cycles5 ((u8)0x05)
+#define ADC_SampleTime_71Cycles5 ((u8)0x06)
+#define ADC_SampleTime_239Cycles5 ((u8)0x07)
+
+#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SampleTime_1Cycles5) || \
+ ((TIME) == ADC_SampleTime_7Cycles5) || \
+ ((TIME) == ADC_SampleTime_13Cycles5) || \
+ ((TIME) == ADC_SampleTime_28Cycles5) || \
+ ((TIME) == ADC_SampleTime_41Cycles5) || \
+ ((TIME) == ADC_SampleTime_55Cycles5) || \
+ ((TIME) == ADC_SampleTime_71Cycles5) || \
+ ((TIME) == ADC_SampleTime_239Cycles5))
+
+/* ADC extrenal trigger sources for injected channels conversion -------------*/
+/* For ADC1 and ADC2 */
+#define ADC_ExternalTrigInjecConv_T2_TRGO ((u32)0x00002000)
+#define ADC_ExternalTrigInjecConv_T2_CC1 ((u32)0x00003000)
+#define ADC_ExternalTrigInjecConv_T3_CC4 ((u32)0x00004000)
+#define ADC_ExternalTrigInjecConv_T4_TRGO ((u32)0x00005000)
+#define ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4 ((u32)0x00006000)
+/* For ADC1, ADC2 and ADC3 */
+#define ADC_ExternalTrigInjecConv_T1_TRGO ((u32)0x00000000)
+#define ADC_ExternalTrigInjecConv_T1_CC4 ((u32)0x00001000)
+#define ADC_ExternalTrigInjecConv_None ((u32)0x00007000)
+/* For ADC3 */
+#define ADC_ExternalTrigInjecConv_T4_CC3 ((u32)0x00002000)
+#define ADC_ExternalTrigInjecConv_T8_CC2 ((u32)0x00003000)
+#define ADC_ExternalTrigInjecConv_T8_CC4 ((u32)0x00004000)
+#define ADC_ExternalTrigInjecConv_T5_TRGO ((u32)0x00005000)
+#define ADC_ExternalTrigInjecConv_T5_CC4 ((u32)0x00006000)
+
+#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_ExternalTrigInjecConv_T1_TRGO) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T1_CC4) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_TRGO) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_CC1) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T3_CC4) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_TRGO) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_None) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC3) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC2) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC4) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_TRGO) || \
+ ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_CC4))
+
+/* ADC injected channel selection --------------------------------------------*/
+#define ADC_InjectedChannel_1 ((u8)0x14)
+#define ADC_InjectedChannel_2 ((u8)0x18)
+#define ADC_InjectedChannel_3 ((u8)0x1C)
+#define ADC_InjectedChannel_4 ((u8)0x20)
+
+#define IS_ADC_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) == ADC_InjectedChannel_1) || \
+ ((CHANNEL) == ADC_InjectedChannel_2) || \
+ ((CHANNEL) == ADC_InjectedChannel_3) || \
+ ((CHANNEL) == ADC_InjectedChannel_4))
+
+/* ADC analog watchdog selection ---------------------------------------------*/
+#define ADC_AnalogWatchdog_SingleRegEnable ((u32)0x00800200)
+#define ADC_AnalogWatchdog_SingleInjecEnable ((u32)0x00400200)
+#define ADC_AnalogWatchdog_SingleRegOrInjecEnable ((u32)0x00C00200)
+#define ADC_AnalogWatchdog_AllRegEnable ((u32)0x00800000)
+#define ADC_AnalogWatchdog_AllInjecEnable ((u32)0x00400000)
+#define ADC_AnalogWatchdog_AllRegAllInjecEnable ((u32)0x00C00000)
+#define ADC_AnalogWatchdog_None ((u32)0x00000000)
+
+#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_AnalogWatchdog_SingleRegEnable) || \
+ ((WATCHDOG) == ADC_AnalogWatchdog_SingleInjecEnable) || \
+ ((WATCHDOG) == ADC_AnalogWatchdog_SingleRegOrInjecEnable) || \
+ ((WATCHDOG) == ADC_AnalogWatchdog_AllRegEnable) || \
+ ((WATCHDOG) == ADC_AnalogWatchdog_AllInjecEnable) || \
+ ((WATCHDOG) == ADC_AnalogWatchdog_AllRegAllInjecEnable) || \
+ ((WATCHDOG) == ADC_AnalogWatchdog_None))
+
+/* ADC interrupts definition -------------------------------------------------*/
+#define ADC_IT_EOC ((u16)0x0220)
+#define ADC_IT_AWD ((u16)0x0140)
+#define ADC_IT_JEOC ((u16)0x0480)
+
+#define IS_ADC_IT(IT) ((((IT) & (u16)0xF81F) == 0x00) && ((IT) != 0x00))
+#define IS_ADC_GET_IT(IT) (((IT) == ADC_IT_EOC) || ((IT) == ADC_IT_AWD) || \
+ ((IT) == ADC_IT_JEOC))
+
+/* ADC flags definition ------------------------------------------------------*/
+#define ADC_FLAG_AWD ((u8)0x01)
+#define ADC_FLAG_EOC ((u8)0x02)
+#define ADC_FLAG_JEOC ((u8)0x04)
+#define ADC_FLAG_JSTRT ((u8)0x08)
+#define ADC_FLAG_STRT ((u8)0x10)
+
+#define IS_ADC_CLEAR_FLAG(FLAG) ((((FLAG) & (u8)0xE0) == 0x00) && ((FLAG) != 0x00))
+#define IS_ADC_GET_FLAG(FLAG) (((FLAG) == ADC_FLAG_AWD) || ((FLAG) == ADC_FLAG_EOC) || \
+ ((FLAG) == ADC_FLAG_JEOC) || ((FLAG)== ADC_FLAG_JSTRT) || \
+ ((FLAG) == ADC_FLAG_STRT))
+
+/* ADC thresholds ------------------------------------------------------------*/
+#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFF)
+
+/* ADC injected offset -------------------------------------------------------*/
+#define IS_ADC_OFFSET(OFFSET) ((OFFSET) <= 0xFFF)
+
+/* ADC injected length -------------------------------------------------------*/
+#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x4))
+
+/* ADC injected rank ---------------------------------------------------------*/
+#define IS_ADC_INJECTED_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x4))
+
+/* ADC regular length --------------------------------------------------------*/
+#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x10))
+
+/* ADC regular rank ----------------------------------------------------------*/
+#define IS_ADC_REGULAR_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x10))
+
+/* ADC regular discontinuous mode number -------------------------------------*/
+#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 0x1) && ((NUMBER) <= 0x8))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void ADC_DeInit(ADC_TypeDef* ADCx);
+void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct);
+void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct);
+void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_ITConfig(ADC_TypeDef* ADCx, u16 ADC_IT, FunctionalState NewState);
+void ADC_ResetCalibration(ADC_TypeDef* ADCx);
+FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx);
+void ADC_StartCalibration(ADC_TypeDef* ADCx);
+FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx);
+void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx);
+void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, u8 Number);
+void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel, u8 Rank, u8 ADC_SampleTime);
+void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+u16 ADC_GetConversionValue(ADC_TypeDef* ADCx);
+u32 ADC_GetDualModeConversionValue(void);
+void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, u32 ADC_ExternalTrigInjecConv);
+void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx);
+void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel, u8 Rank, u8 ADC_SampleTime);
+void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, u8 Length);
+void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, u8 ADC_InjectedChannel, u16 Offset);
+u16 ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, u8 ADC_InjectedChannel);
+void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, u32 ADC_AnalogWatchdog);
+void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, u16 HighThreshold, u16 LowThreshold);
+void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel);
+void ADC_TempSensorVrefintCmd(FunctionalState NewState);
+FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, u8 ADC_FLAG);
+void ADC_ClearFlag(ADC_TypeDef* ADCx, u8 ADC_FLAG);
+ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, u16 ADC_IT);
+void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, u16 ADC_IT);
+
+#endif /*__STM32F10x_ADC_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_bkp.h b/src/stm32lib/inc/stm32f10x_bkp.h new file mode 100644 index 0000000..39ea7ae --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_bkp.h @@ -0,0 +1,122 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_bkp.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* BKP firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_BKP_H
+#define __STM32F10x_BKP_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Tamper Pin active level */
+#define BKP_TamperPinLevel_High ((u16)0x0000)
+#define BKP_TamperPinLevel_Low ((u16)0x0001)
+
+#define IS_BKP_TAMPER_PIN_LEVEL(LEVEL) (((LEVEL) == BKP_TamperPinLevel_High) || \
+ ((LEVEL) == BKP_TamperPinLevel_Low))
+
+/* RTC output source to output on the Tamper pin */
+#define BKP_RTCOutputSource_None ((u16)0x0000)
+#define BKP_RTCOutputSource_CalibClock ((u16)0x0080)
+#define BKP_RTCOutputSource_Alarm ((u16)0x0100)
+#define BKP_RTCOutputSource_Second ((u16)0x0300)
+
+#define IS_BKP_RTC_OUTPUT_SOURCE(SOURCE) (((SOURCE) == BKP_RTCOutputSource_None) || \
+ ((SOURCE) == BKP_RTCOutputSource_CalibClock) || \
+ ((SOURCE) == BKP_RTCOutputSource_Alarm) || \
+ ((SOURCE) == BKP_RTCOutputSource_Second))
+
+/* Data Backup Register */
+#define BKP_DR1 ((u16)0x0004)
+#define BKP_DR2 ((u16)0x0008)
+#define BKP_DR3 ((u16)0x000C)
+#define BKP_DR4 ((u16)0x0010)
+#define BKP_DR5 ((u16)0x0014)
+#define BKP_DR6 ((u16)0x0018)
+#define BKP_DR7 ((u16)0x001C)
+#define BKP_DR8 ((u16)0x0020)
+#define BKP_DR9 ((u16)0x0024)
+#define BKP_DR10 ((u16)0x0028)
+#define BKP_DR11 ((u16)0x0040)
+#define BKP_DR12 ((u16)0x0044)
+#define BKP_DR13 ((u16)0x0048)
+#define BKP_DR14 ((u16)0x004C)
+#define BKP_DR15 ((u16)0x0050)
+#define BKP_DR16 ((u16)0x0054)
+#define BKP_DR17 ((u16)0x0058)
+#define BKP_DR18 ((u16)0x005C)
+#define BKP_DR19 ((u16)0x0060)
+#define BKP_DR20 ((u16)0x0064)
+#define BKP_DR21 ((u16)0x0068)
+#define BKP_DR22 ((u16)0x006C)
+#define BKP_DR23 ((u16)0x0070)
+#define BKP_DR24 ((u16)0x0074)
+#define BKP_DR25 ((u16)0x0078)
+#define BKP_DR26 ((u16)0x007C)
+#define BKP_DR27 ((u16)0x0080)
+#define BKP_DR28 ((u16)0x0084)
+#define BKP_DR29 ((u16)0x0088)
+#define BKP_DR30 ((u16)0x008C)
+#define BKP_DR31 ((u16)0x0090)
+#define BKP_DR32 ((u16)0x0094)
+#define BKP_DR33 ((u16)0x0098)
+#define BKP_DR34 ((u16)0x009C)
+#define BKP_DR35 ((u16)0x00A0)
+#define BKP_DR36 ((u16)0x00A4)
+#define BKP_DR37 ((u16)0x00A8)
+#define BKP_DR38 ((u16)0x00AC)
+#define BKP_DR39 ((u16)0x00B0)
+#define BKP_DR40 ((u16)0x00B4)
+#define BKP_DR41 ((u16)0x00B8)
+#define BKP_DR42 ((u16)0x00BC)
+
+#define IS_BKP_DR(DR) (((DR) == BKP_DR1) || ((DR) == BKP_DR2) || ((DR) == BKP_DR3) || \
+ ((DR) == BKP_DR4) || ((DR) == BKP_DR5) || ((DR) == BKP_DR6) || \
+ ((DR) == BKP_DR7) || ((DR) == BKP_DR8) || ((DR) == BKP_DR9) || \
+ ((DR) == BKP_DR10) || ((DR) == BKP_DR11) || ((DR) == BKP_DR12) || \
+ ((DR) == BKP_DR13) || ((DR) == BKP_DR14) || ((DR) == BKP_DR15) || \
+ ((DR) == BKP_DR16) || ((DR) == BKP_DR17) || ((DR) == BKP_DR18) || \
+ ((DR) == BKP_DR19) || ((DR) == BKP_DR20) || ((DR) == BKP_DR21) || \
+ ((DR) == BKP_DR22) || ((DR) == BKP_DR23) || ((DR) == BKP_DR24) || \
+ ((DR) == BKP_DR25) || ((DR) == BKP_DR26) || ((DR) == BKP_DR27) || \
+ ((DR) == BKP_DR28) || ((DR) == BKP_DR29) || ((DR) == BKP_DR30) || \
+ ((DR) == BKP_DR31) || ((DR) == BKP_DR32) || ((DR) == BKP_DR33) || \
+ ((DR) == BKP_DR34) || ((DR) == BKP_DR35) || ((DR) == BKP_DR36) || \
+ ((DR) == BKP_DR37) || ((DR) == BKP_DR38) || ((DR) == BKP_DR39) || \
+ ((DR) == BKP_DR40) || ((DR) == BKP_DR41) || ((DR) == BKP_DR42))
+
+#define IS_BKP_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x7F)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void BKP_DeInit(void);
+void BKP_TamperPinLevelConfig(u16 BKP_TamperPinLevel);
+void BKP_TamperPinCmd(FunctionalState NewState);
+void BKP_ITConfig(FunctionalState NewState);
+void BKP_RTCOutputConfig(u16 BKP_RTCOutputSource);
+void BKP_SetRTCCalibrationValue(u8 CalibrationValue);
+void BKP_WriteBackupRegister(u16 BKP_DR, u16 Data);
+u16 BKP_ReadBackupRegister(u16 BKP_DR);
+FlagStatus BKP_GetFlagStatus(void);
+void BKP_ClearFlag(void);
+ITStatus BKP_GetITStatus(void);
+void BKP_ClearITPendingBit(void);
+
+#endif /* __STM32F10x_BKP_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_can.h b/src/stm32lib/inc/stm32f10x_can.h new file mode 100644 index 0000000..85dd07b --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_can.h @@ -0,0 +1,263 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_can.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* CAN firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CAN_H
+#define __STM32F10x_CAN_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* CAN init structure definition */
+typedef struct
+{
+ FunctionalState CAN_TTCM;
+ FunctionalState CAN_ABOM;
+ FunctionalState CAN_AWUM;
+ FunctionalState CAN_NART;
+ FunctionalState CAN_RFLM;
+ FunctionalState CAN_TXFP;
+ u8 CAN_Mode;
+ u8 CAN_SJW;
+ u8 CAN_BS1;
+ u8 CAN_BS2;
+ u16 CAN_Prescaler;
+} CAN_InitTypeDef;
+
+/* CAN filter init structure definition */
+typedef struct
+{
+ u8 CAN_FilterNumber;
+ u8 CAN_FilterMode;
+ u8 CAN_FilterScale;
+ u16 CAN_FilterIdHigh;
+ u16 CAN_FilterIdLow;
+ u16 CAN_FilterMaskIdHigh;
+ u16 CAN_FilterMaskIdLow;
+ u16 CAN_FilterFIFOAssignment;
+ FunctionalState CAN_FilterActivation;
+} CAN_FilterInitTypeDef;
+
+/* CAN Tx message structure definition */
+typedef struct
+{
+ u32 StdId;
+ u32 ExtId;
+ u8 IDE;
+ u8 RTR;
+ u8 DLC;
+ u8 Data[8];
+} CanTxMsg;
+
+/* CAN Rx message structure definition */
+typedef struct
+{
+ u32 StdId;
+ u32 ExtId;
+ u8 IDE;
+ u8 RTR;
+ u8 DLC;
+ u8 Data[8];
+ u8 FMI;
+} CanRxMsg;
+
+/* Exported constants --------------------------------------------------------*/
+
+/* CAN sleep constants */
+#define CANINITFAILED ((u8)0x00) /* CAN initialization failed */
+#define CANINITOK ((u8)0x01) /* CAN initialization failed */
+
+/* CAN operating mode */
+#define CAN_Mode_Normal ((u8)0x00) /* normal mode */
+#define CAN_Mode_LoopBack ((u8)0x01) /* loopback mode */
+#define CAN_Mode_Silent ((u8)0x02) /* silent mode */
+#define CAN_Mode_Silent_LoopBack ((u8)0x03) /* loopback combined with silent mode */
+
+#define IS_CAN_MODE(MODE) (((MODE) == CAN_Mode_Normal) || ((MODE) == CAN_Mode_LoopBack)|| \
+ ((MODE) == CAN_Mode_Silent) || ((MODE) == CAN_Mode_Silent_LoopBack))
+
+/* CAN synchronisation jump width */
+#define CAN_SJW_1tq ((u8)0x00) /* 1 time quantum */
+#define CAN_SJW_2tq ((u8)0x01) /* 2 time quantum */
+#define CAN_SJW_3tq ((u8)0x02) /* 3 time quantum */
+#define CAN_SJW_4tq ((u8)0x03) /* 4 time quantum */
+
+#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1tq) || ((SJW) == CAN_SJW_2tq)|| \
+ ((SJW) == CAN_SJW_3tq) || ((SJW) == CAN_SJW_4tq))
+
+/* time quantum in bit segment 1 */
+#define CAN_BS1_1tq ((u8)0x00) /* 1 time quantum */
+#define CAN_BS1_2tq ((u8)0x01) /* 2 time quantum */
+#define CAN_BS1_3tq ((u8)0x02) /* 3 time quantum */
+#define CAN_BS1_4tq ((u8)0x03) /* 4 time quantum */
+#define CAN_BS1_5tq ((u8)0x04) /* 5 time quantum */
+#define CAN_BS1_6tq ((u8)0x05) /* 6 time quantum */
+#define CAN_BS1_7tq ((u8)0x06) /* 7 time quantum */
+#define CAN_BS1_8tq ((u8)0x07) /* 8 time quantum */
+#define CAN_BS1_9tq ((u8)0x08) /* 9 time quantum */
+#define CAN_BS1_10tq ((u8)0x09) /* 10 time quantum */
+#define CAN_BS1_11tq ((u8)0x0A) /* 11 time quantum */
+#define CAN_BS1_12tq ((u8)0x0B) /* 12 time quantum */
+#define CAN_BS1_13tq ((u8)0x0C) /* 13 time quantum */
+#define CAN_BS1_14tq ((u8)0x0D) /* 14 time quantum */
+#define CAN_BS1_15tq ((u8)0x0E) /* 15 time quantum */
+#define CAN_BS1_16tq ((u8)0x0F) /* 16 time quantum */
+
+#define IS_CAN_BS1(BS1) ((BS1) <= CAN_BS1_16tq)
+
+/* time quantum in bit segment 2 */
+#define CAN_BS2_1tq ((u8)0x00) /* 1 time quantum */
+#define CAN_BS2_2tq ((u8)0x01) /* 2 time quantum */
+#define CAN_BS2_3tq ((u8)0x02) /* 3 time quantum */
+#define CAN_BS2_4tq ((u8)0x03) /* 4 time quantum */
+#define CAN_BS2_5tq ((u8)0x04) /* 5 time quantum */
+#define CAN_BS2_6tq ((u8)0x05) /* 6 time quantum */
+#define CAN_BS2_7tq ((u8)0x06) /* 7 time quantum */
+#define CAN_BS2_8tq ((u8)0x07) /* 8 time quantum */
+
+#define IS_CAN_BS2(BS2) ((BS2) <= CAN_BS2_8tq)
+
+/* CAN clock prescaler */
+#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1) && ((PRESCALER) <= 1024))
+
+/* CAN filter number */
+#define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 13)
+
+/* CAN filter mode */
+#define CAN_FilterMode_IdMask ((u8)0x00) /* id/mask mode */
+#define CAN_FilterMode_IdList ((u8)0x01) /* identifier list mode */
+
+#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FilterMode_IdMask) || \
+ ((MODE) == CAN_FilterMode_IdList))
+
+/* CAN filter scale */
+#define CAN_FilterScale_16bit ((u8)0x00) /* 16-bit filter scale */
+#define CAN_FilterScale_32bit ((u8)0x01) /* 2-bit filter scale */
+
+#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FilterScale_16bit) || \
+ ((SCALE) == CAN_FilterScale_32bit))
+
+/* CAN filter FIFO assignation */
+#define CAN_FilterFIFO0 ((u8)0x00) /* Filter FIFO 0 assignment for filter x */
+#define CAN_FilterFIFO1 ((u8)0x01) /* Filter FIFO 1 assignment for filter x */
+
+#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FilterFIFO0) || \
+ ((FIFO) == CAN_FilterFIFO1))
+
+/* CAN Tx */
+#define IS_CAN_TRANSMITMAILBOX(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= ((u8)0x02))
+#define IS_CAN_STDID(STDID) ((STDID) <= ((u32)0x7FF))
+#define IS_CAN_EXTID(EXTID) ((EXTID) <= ((u32)0x1FFFFFFF))
+#define IS_CAN_DLC(DLC) ((DLC) <= ((u8)0x08))
+
+/* CAN identifier type */
+#define CAN_ID_STD ((u32)0x00000000) /* Standard Id */
+#define CAN_ID_EXT ((u32)0x00000004) /* Extended Id */
+
+#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_ID_STD) || ((IDTYPE) == CAN_ID_EXT))
+
+/* CAN remote transmission request */
+#define CAN_RTR_DATA ((u32)0x00000000) /* Data frame */
+#define CAN_RTR_REMOTE ((u32)0x00000002) /* Remote frame */
+
+#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_DATA) || ((RTR) == CAN_RTR_REMOTE))
+
+/* CAN transmit constants */
+#define CANTXFAILED ((u8)0x00) /* CAN transmission failed */
+#define CANTXOK ((u8)0x01) /* CAN transmission succeeded */
+#define CANTXPENDING ((u8)0x02) /* CAN transmission pending */
+#define CAN_NO_MB ((u8)0x04) /* CAN cell did not provide an empty mailbox */
+
+/* CAN receive FIFO number constants */
+#define CAN_FIFO0 ((u8)0x00) /* CAN FIFO0 used to receive */
+#define CAN_FIFO1 ((u8)0x01) /* CAN FIFO1 used to receive */
+
+#define IS_CAN_FIFO(FIFO) (((FIFO) == CAN_FIFO0) || ((FIFO) == CAN_FIFO1))
+
+/* CAN sleep constants */
+#define CANSLEEPFAILED ((u8)0x00) /* CAN did not enter the sleep mode */
+#define CANSLEEPOK ((u8)0x01) /* CAN entered the sleep mode */
+
+/* CAN wake up constants */
+#define CANWAKEUPFAILED ((u8)0x00) /* CAN did not leave the sleep mode */
+#define CANWAKEUPOK ((u8)0x01) /* CAN leaved the sleep mode */
+
+/* CAN flags */
+#define CAN_FLAG_EWG ((u32)0x00000001) /* Error Warning Flag */
+#define CAN_FLAG_EPV ((u32)0x00000002) /* Error Passive Flag */
+#define CAN_FLAG_BOF ((u32)0x00000004) /* Bus-Off Flag */
+
+#define IS_CAN_FLAG(FLAG) (((FLAG) == CAN_FLAG_EWG) || ((FLAG) == CAN_FLAG_EPV) ||\
+ ((FLAG) == CAN_FLAG_BOF))
+
+/* CAN interrupts */
+#define CAN_IT_RQCP0 ((u32)0x00000005) /* Request completed mailbox 0 */
+#define CAN_IT_RQCP1 ((u32)0x00000006) /* Request completed mailbox 1 */
+#define CAN_IT_RQCP2 ((u32)0x00000007) /* Request completed mailbox 2 */
+#define CAN_IT_TME ((u32)0x00000001) /* Transmit mailbox empty */
+#define CAN_IT_FMP0 ((u32)0x00000002) /* FIFO 0 message pending */
+#define CAN_IT_FF0 ((u32)0x00000004) /* FIFO 0 full */
+#define CAN_IT_FOV0 ((u32)0x00000008) /* FIFO 0 overrun */
+#define CAN_IT_FMP1 ((u32)0x00000010) /* FIFO 1 message pending */
+#define CAN_IT_FF1 ((u32)0x00000020) /* FIFO 1 full */
+#define CAN_IT_FOV1 ((u32)0x00000040) /* FIFO 1 overrun */
+#define CAN_IT_EWG ((u32)0x00000100) /* Error warning */
+#define CAN_IT_EPV ((u32)0x00000200) /* Error passive */
+#define CAN_IT_BOF ((u32)0x00000400) /* Bus-off */
+#define CAN_IT_LEC ((u32)0x00000800) /* Last error code */
+#define CAN_IT_ERR ((u32)0x00008000) /* Error */
+#define CAN_IT_WKU ((u32)0x00010000) /* Wake-up */
+#define CAN_IT_SLK ((u32)0x00020000) /* Sleep */
+
+#define IS_CAN_ITConfig(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FMP0) ||\
+ ((IT) == CAN_IT_FF0) || ((IT) == CAN_IT_FOV0) ||\
+ ((IT) == CAN_IT_FMP1) || ((IT) == CAN_IT_FF1) ||\
+ ((IT) == CAN_IT_FOV1) || ((IT) == CAN_IT_EWG) ||\
+ ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\
+ ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\
+ ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK))
+
+#define IS_CAN_ITStatus(IT) (((IT) == CAN_IT_RQCP0) || ((IT) == CAN_IT_RQCP1) ||\
+ ((IT) == CAN_IT_RQCP2) || ((IT) == CAN_IT_FF0) ||\
+ ((IT) == CAN_IT_FOV0) || ((IT) == CAN_IT_FF1) ||\
+ ((IT) == CAN_IT_FOV1) || ((IT) == CAN_IT_EWG) ||\
+ ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\
+ ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported function protypes ----------------------------------------------- */
+void CAN_DeInit(void);
+u8 CAN_Init(CAN_InitTypeDef* CAN_InitStruct);
+void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct);
+void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct);
+void CAN_ITConfig(u32 CAN_IT, FunctionalState NewState);
+u8 CAN_Transmit(CanTxMsg* TxMessage);
+u8 CAN_TransmitStatus(u8 TransmitMailbox);
+void CAN_CancelTransmit(u8 Mailbox);
+void CAN_FIFORelease(u8 FIFONumber);
+u8 CAN_MessagePending(u8 FIFONumber);
+void CAN_Receive(u8 FIFONumber, CanRxMsg* RxMessage);
+u8 CAN_Sleep(void);
+u8 CAN_WakeUp(void);
+FlagStatus CAN_GetFlagStatus(u32 CAN_FLAG);
+void CAN_ClearFlag(u32 CAN_FLAG);
+ITStatus CAN_GetITStatus(u32 CAN_IT);
+void CAN_ClearITPendingBit(u32 CAN_IT);
+
+#endif /* __STM32F10x_CAN_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_crc.h b/src/stm32lib/inc/stm32f10x_crc.h new file mode 100644 index 0000000..0c3dab4 --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_crc.h @@ -0,0 +1,37 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_crc.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* CRC firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CRC_H
+#define __STM32F10x_CRC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void CRC_ResetDR(void);
+u32 CRC_CalcCRC(u32 Data);
+u32 CRC_CalcBlockCRC(u32 pBuffer[], u32 BufferLength);
+u32 CRC_GetCRC(void);
+void CRC_SetIDRegister(u8 IDValue);
+u8 CRC_GetIDRegister(void);
+
+#endif /* __STM32F10x_CRC_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_dac.h b/src/stm32lib/inc/stm32f10x_dac.h new file mode 100644 index 0000000..cd7b5ad --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_dac.h @@ -0,0 +1,167 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_dac.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* DAC firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_DAC_H
+#define __STM32F10x_DAC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* DAC Init structure definition */
+typedef struct
+{
+ u32 DAC_Trigger;
+ u32 DAC_WaveGeneration;
+ u32 DAC_LFSRUnmask_TriangleAmplitude;
+ u32 DAC_OutputBuffer;
+}DAC_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+/* DAC trigger selection */
+#define DAC_Trigger_None ((u32)0x00000000)
+#define DAC_Trigger_T6_TRGO ((u32)0x00000004)
+#define DAC_Trigger_T8_TRGO ((u32)0x0000000C)
+#define DAC_Trigger_T7_TRGO ((u32)0x00000014)
+#define DAC_Trigger_T5_TRGO ((u32)0x0000001C)
+#define DAC_Trigger_T2_TRGO ((u32)0x00000024)
+#define DAC_Trigger_T4_TRGO ((u32)0x0000002C)
+#define DAC_Trigger_Ext_IT9 ((u32)0x00000034)
+#define DAC_Trigger_Software ((u32)0x0000003C)
+
+#define IS_DAC_TRIGGER(TRIGGER) (((TRIGGER) == DAC_Trigger_None) || \
+ ((TRIGGER) == DAC_Trigger_T6_TRGO) || \
+ ((TRIGGER) == DAC_Trigger_T8_TRGO) || \
+ ((TRIGGER) == DAC_Trigger_T7_TRGO) || \
+ ((TRIGGER) == DAC_Trigger_T5_TRGO) || \
+ ((TRIGGER) == DAC_Trigger_T2_TRGO) || \
+ ((TRIGGER) == DAC_Trigger_T4_TRGO) || \
+ ((TRIGGER) == DAC_Trigger_Ext_IT9) || \
+ ((TRIGGER) == DAC_Trigger_Software))
+
+/* DAC wave generation */
+#define DAC_WaveGeneration_None ((u32)0x00000000)
+#define DAC_WaveGeneration_Noise ((u32)0x00000040)
+#define DAC_WaveGeneration_Triangle ((u32)0x00000080)
+
+#define IS_DAC_GENERATE_WAVE(WAVE) (((WAVE) == DAC_WaveGeneration_None) || \
+ ((WAVE) == DAC_WaveGeneration_Noise) || \
+ ((WAVE) == DAC_WaveGeneration_Triangle))
+
+/* DAC noise wave generation mask / triangle wave generation max amplitude */
+#define DAC_LFSRUnmask_Bit0 ((u32)0x00000000)
+#define DAC_LFSRUnmask_Bits1_0 ((u32)0x00000100)
+#define DAC_LFSRUnmask_Bits2_0 ((u32)0x00000200)
+#define DAC_LFSRUnmask_Bits3_0 ((u32)0x00000300)
+#define DAC_LFSRUnmask_Bits4_0 ((u32)0x00000400)
+#define DAC_LFSRUnmask_Bits5_0 ((u32)0x00000500)
+#define DAC_LFSRUnmask_Bits6_0 ((u32)0x00000600)
+#define DAC_LFSRUnmask_Bits7_0 ((u32)0x00000700)
+#define DAC_LFSRUnmask_Bits8_0 ((u32)0x00000800)
+#define DAC_LFSRUnmask_Bits9_0 ((u32)0x00000900)
+#define DAC_LFSRUnmask_Bits10_0 ((u32)0x00000A00)
+#define DAC_LFSRUnmask_Bits11_0 ((u32)0x00000B00)
+
+#define DAC_TriangleAmplitude_1 ((u32)0x00000000)
+#define DAC_TriangleAmplitude_3 ((u32)0x00000100)
+#define DAC_TriangleAmplitude_7 ((u32)0x00000200)
+#define DAC_TriangleAmplitude_15 ((u32)0x00000300)
+#define DAC_TriangleAmplitude_31 ((u32)0x00000400)
+#define DAC_TriangleAmplitude_63 ((u32)0x00000500)
+#define DAC_TriangleAmplitude_127 ((u32)0x00000600)
+#define DAC_TriangleAmplitude_255 ((u32)0x00000700)
+#define DAC_TriangleAmplitude_511 ((u32)0x00000800)
+#define DAC_TriangleAmplitude_1023 ((u32)0x00000900)
+#define DAC_TriangleAmplitude_2047 ((u32)0x00000A00)
+#define DAC_TriangleAmplitude_4095 ((u32)0x00000B00)
+
+#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUnmask_Bit0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits1_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits2_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits3_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits4_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits5_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits6_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits7_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits8_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits9_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits10_0) || \
+ ((VALUE) == DAC_LFSRUnmask_Bits11_0) || \
+ ((VALUE) == DAC_TriangleAmplitude_1) || \
+ ((VALUE) == DAC_TriangleAmplitude_3) || \
+ ((VALUE) == DAC_TriangleAmplitude_7) || \
+ ((VALUE) == DAC_TriangleAmplitude_15) || \
+ ((VALUE) == DAC_TriangleAmplitude_31) || \
+ ((VALUE) == DAC_TriangleAmplitude_63) || \
+ ((VALUE) == DAC_TriangleAmplitude_127) || \
+ ((VALUE) == DAC_TriangleAmplitude_255) || \
+ ((VALUE) == DAC_TriangleAmplitude_511) || \
+ ((VALUE) == DAC_TriangleAmplitude_1023) || \
+ ((VALUE) == DAC_TriangleAmplitude_2047) || \
+ ((VALUE) == DAC_TriangleAmplitude_4095))
+
+/* DAC output buffer */
+#define DAC_OutputBuffer_Enable ((u32)0x00000000)
+#define DAC_OutputBuffer_Disable ((u32)0x00000002)
+
+#define IS_DAC_OUTPUT_BUFFER_STATE(STATE) (((STATE) == DAC_OutputBuffer_Enable) || \
+ ((STATE) == DAC_OutputBuffer_Disable))
+
+/* DAC Channel selection */
+#define DAC_Channel_1 ((u32)0x00000000)
+#define DAC_Channel_2 ((u32)0x00000010)
+
+#define IS_DAC_CHANNEL(CHANNEL) (((CHANNEL) == DAC_Channel_1) || \
+ ((CHANNEL) == DAC_Channel_2))
+
+/* DAC data alignement */
+#define DAC_Align_12b_R ((u32)0x00000000)
+#define DAC_Align_12b_L ((u32)0x00000004)
+#define DAC_Align_8b_R ((u32)0x00000008)
+
+#define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_Align_12b_R) || \
+ ((ALIGN) == DAC_Align_12b_L) || \
+ ((ALIGN) == DAC_Align_8b_R))
+
+/* DAC wave generation */
+#define DAC_Wave_Noise ((u32)0x00000040)
+#define DAC_Wave_Triangle ((u32)0x00000080)
+
+#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_Wave_Noise) || \
+ ((WAVE) == DAC_Wave_Triangle))
+
+/* DAC data ------------------------------------------------------------------*/
+#define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+void DAC_DeInit(void);
+void DAC_Init(u32 DAC_Channel, DAC_InitTypeDef* DAC_InitStruct);
+void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct);
+void DAC_Cmd(u32 DAC_Channel, FunctionalState NewState);
+void DAC_DMACmd(u32 DAC_Channel, FunctionalState NewState);
+void DAC_SoftwareTriggerCmd(u32 DAC_Channel, FunctionalState NewState);
+void DAC_DualSoftwareTriggerCmd(FunctionalState NewState);
+void DAC_WaveGenerationCmd(u32 DAC_Channel, u32 DAC_Wave, FunctionalState NewState);
+void DAC_SetChannel1Data(u32 DAC_Align, u16 Data);
+void DAC_SetChannel2Data(u32 DAC_Align, u16 Data);
+void DAC_SetDualChannelData(u32 DAC_Align, u16 Data2, u16 Data1);
+u16 DAC_GetDataOutputValue(u32 DAC_Channel);
+
+#endif /*__STM32F10x_DAC_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_dbgmcu.h b/src/stm32lib/inc/stm32f10x_dbgmcu.h new file mode 100644 index 0000000..212f646 --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_dbgmcu.h @@ -0,0 +1,55 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_dbgmcu.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* DBGMCU firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_DBGMCU_H
+#define __STM32F10x_DBGMCU_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+#define DBGMCU_SLEEP ((u32)0x00000001)
+#define DBGMCU_STOP ((u32)0x00000002)
+#define DBGMCU_STANDBY ((u32)0x00000004)
+#define DBGMCU_IWDG_STOP ((u32)0x00000100)
+#define DBGMCU_WWDG_STOP ((u32)0x00000200)
+#define DBGMCU_TIM1_STOP ((u32)0x00000400)
+#define DBGMCU_TIM2_STOP ((u32)0x00000800)
+#define DBGMCU_TIM3_STOP ((u32)0x00001000)
+#define DBGMCU_TIM4_STOP ((u32)0x00002000)
+#define DBGMCU_CAN_STOP ((u32)0x00004000)
+#define DBGMCU_I2C1_SMBUS_TIMEOUT ((u32)0x00008000)
+#define DBGMCU_I2C2_SMBUS_TIMEOUT ((u32)0x00010000)
+#define DBGMCU_TIM5_STOP ((u32)0x00020000)
+#define DBGMCU_TIM6_STOP ((u32)0x00040000)
+#define DBGMCU_TIM7_STOP ((u32)0x00080000)
+#define DBGMCU_TIM8_STOP ((u32)0x00100000)
+
+#define IS_DBGMCU_PERIPH(PERIPH) ((((PERIPH) & 0xFFE000F8) == 0x00) && ((PERIPH) != 0x00))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+u32 DBGMCU_GetREVID(void);
+u32 DBGMCU_GetDEVID(void);
+void DBGMCU_Config(u32 DBGMCU_Periph, FunctionalState NewState);
+
+#endif /* __STM32F10x_DBGMCU_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
+
+
diff --git a/src/stm32lib/inc/stm32f10x_dma.h b/src/stm32lib/inc/stm32f10x_dma.h new file mode 100644 index 0000000..4803a69 --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_dma.h @@ -0,0 +1,297 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_dma.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* DMA firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_DMA_H
+#define __STM32F10x_DMA_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* DMA Init structure definition */
+typedef struct
+{
+ u32 DMA_PeripheralBaseAddr;
+ u32 DMA_MemoryBaseAddr;
+ u32 DMA_DIR;
+ u32 DMA_BufferSize;
+ u32 DMA_PeripheralInc;
+ u32 DMA_MemoryInc;
+ u32 DMA_PeripheralDataSize;
+ u32 DMA_MemoryDataSize;
+ u32 DMA_Mode;
+ u32 DMA_Priority;
+ u32 DMA_M2M;
+}DMA_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+#define IS_DMA_ALL_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == DMA1_Channel1_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA1_Channel2_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA1_Channel3_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA1_Channel4_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA1_Channel5_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA1_Channel6_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA1_Channel7_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA2_Channel1_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA2_Channel2_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA2_Channel3_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA2_Channel4_BASE) || \
+ ((*(u32*)&(PERIPH)) == DMA2_Channel5_BASE))
+
+/* DMA data transfer direction -----------------------------------------------*/
+#define DMA_DIR_PeripheralDST ((u32)0x00000010)
+#define DMA_DIR_PeripheralSRC ((u32)0x00000000)
+
+#define IS_DMA_DIR(DIR) (((DIR) == DMA_DIR_PeripheralDST) || \
+ ((DIR) == DMA_DIR_PeripheralSRC))
+
+/* DMA peripheral incremented mode -------------------------------------------*/
+#define DMA_PeripheralInc_Enable ((u32)0x00000040)
+#define DMA_PeripheralInc_Disable ((u32)0x00000000)
+
+#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PeripheralInc_Enable) || \
+ ((STATE) == DMA_PeripheralInc_Disable))
+
+/* DMA memory incremented mode -----------------------------------------------*/
+#define DMA_MemoryInc_Enable ((u32)0x00000080)
+#define DMA_MemoryInc_Disable ((u32)0x00000000)
+
+#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MemoryInc_Enable) || \
+ ((STATE) == DMA_MemoryInc_Disable))
+
+/* DMA peripheral data size --------------------------------------------------*/
+#define DMA_PeripheralDataSize_Byte ((u32)0x00000000)
+#define DMA_PeripheralDataSize_HalfWord ((u32)0x00000100)
+#define DMA_PeripheralDataSize_Word ((u32)0x00000200)
+
+#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PeripheralDataSize_Byte) || \
+ ((SIZE) == DMA_PeripheralDataSize_HalfWord) || \
+ ((SIZE) == DMA_PeripheralDataSize_Word))
+
+/* DMA memory data size ------------------------------------------------------*/
+#define DMA_MemoryDataSize_Byte ((u32)0x00000000)
+#define DMA_MemoryDataSize_HalfWord ((u32)0x00000400)
+#define DMA_MemoryDataSize_Word ((u32)0x00000800)
+
+#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MemoryDataSize_Byte) || \
+ ((SIZE) == DMA_MemoryDataSize_HalfWord) || \
+ ((SIZE) == DMA_MemoryDataSize_Word))
+
+/* DMA circular/normal mode --------------------------------------------------*/
+#define DMA_Mode_Circular ((u32)0x00000020)
+#define DMA_Mode_Normal ((u32)0x00000000)
+
+#define IS_DMA_MODE(MODE) (((MODE) == DMA_Mode_Circular) || ((MODE) == DMA_Mode_Normal))
+
+/* DMA priority level --------------------------------------------------------*/
+#define DMA_Priority_VeryHigh ((u32)0x00003000)
+#define DMA_Priority_High ((u32)0x00002000)
+#define DMA_Priority_Medium ((u32)0x00001000)
+#define DMA_Priority_Low ((u32)0x00000000)
+
+#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_Priority_VeryHigh) || \
+ ((PRIORITY) == DMA_Priority_High) || \
+ ((PRIORITY) == DMA_Priority_Medium) || \
+ ((PRIORITY) == DMA_Priority_Low))
+
+/* DMA memory to memory ------------------------------------------------------*/
+#define DMA_M2M_Enable ((u32)0x00004000)
+#define DMA_M2M_Disable ((u32)0x00000000)
+
+#define IS_DMA_M2M_STATE(STATE) (((STATE) == DMA_M2M_Enable) || ((STATE) == DMA_M2M_Disable))
+
+/* DMA interrupts definition -------------------------------------------------*/
+#define DMA_IT_TC ((u32)0x00000002)
+#define DMA_IT_HT ((u32)0x00000004)
+#define DMA_IT_TE ((u32)0x00000008)
+
+#define IS_DMA_CONFIG_IT(IT) ((((IT) & 0xFFFFFFF1) == 0x00) && ((IT) != 0x00))
+
+/* For DMA1 */
+#define DMA1_IT_GL1 ((u32)0x00000001)
+#define DMA1_IT_TC1 ((u32)0x00000002)
+#define DMA1_IT_HT1 ((u32)0x00000004)
+#define DMA1_IT_TE1 ((u32)0x00000008)
+#define DMA1_IT_GL2 ((u32)0x00000010)
+#define DMA1_IT_TC2 ((u32)0x00000020)
+#define DMA1_IT_HT2 ((u32)0x00000040)
+#define DMA1_IT_TE2 ((u32)0x00000080)
+#define DMA1_IT_GL3 ((u32)0x00000100)
+#define DMA1_IT_TC3 ((u32)0x00000200)
+#define DMA1_IT_HT3 ((u32)0x00000400)
+#define DMA1_IT_TE3 ((u32)0x00000800)
+#define DMA1_IT_GL4 ((u32)0x00001000)
+#define DMA1_IT_TC4 ((u32)0x00002000)
+#define DMA1_IT_HT4 ((u32)0x00004000)
+#define DMA1_IT_TE4 ((u32)0x00008000)
+#define DMA1_IT_GL5 ((u32)0x00010000)
+#define DMA1_IT_TC5 ((u32)0x00020000)
+#define DMA1_IT_HT5 ((u32)0x00040000)
+#define DMA1_IT_TE5 ((u32)0x00080000)
+#define DMA1_IT_GL6 ((u32)0x00100000)
+#define DMA1_IT_TC6 ((u32)0x00200000)
+#define DMA1_IT_HT6 ((u32)0x00400000)
+#define DMA1_IT_TE6 ((u32)0x00800000)
+#define DMA1_IT_GL7 ((u32)0x01000000)
+#define DMA1_IT_TC7 ((u32)0x02000000)
+#define DMA1_IT_HT7 ((u32)0x04000000)
+#define DMA1_IT_TE7 ((u32)0x08000000)
+/* For DMA2 */
+#define DMA2_IT_GL1 ((u32)0x10000001)
+#define DMA2_IT_TC1 ((u32)0x10000002)
+#define DMA2_IT_HT1 ((u32)0x10000004)
+#define DMA2_IT_TE1 ((u32)0x10000008)
+#define DMA2_IT_GL2 ((u32)0x10000010)
+#define DMA2_IT_TC2 ((u32)0x10000020)
+#define DMA2_IT_HT2 ((u32)0x10000040)
+#define DMA2_IT_TE2 ((u32)0x10000080)
+#define DMA2_IT_GL3 ((u32)0x10000100)
+#define DMA2_IT_TC3 ((u32)0x10000200)
+#define DMA2_IT_HT3 ((u32)0x10000400)
+#define DMA2_IT_TE3 ((u32)0x10000800)
+#define DMA2_IT_GL4 ((u32)0x10001000)
+#define DMA2_IT_TC4 ((u32)0x10002000)
+#define DMA2_IT_HT4 ((u32)0x10004000)
+#define DMA2_IT_TE4 ((u32)0x10008000)
+#define DMA2_IT_GL5 ((u32)0x10010000)
+#define DMA2_IT_TC5 ((u32)0x10020000)
+#define DMA2_IT_HT5 ((u32)0x10040000)
+#define DMA2_IT_TE5 ((u32)0x10080000)
+
+#define IS_DMA_CLEAR_IT(IT) (((((IT) & 0xF0000000) == 0x00) || (((IT) & 0xEFF00000) == 0x00)) && ((IT) != 0x00))
+#define IS_DMA_GET_IT(IT) (((IT) == DMA1_IT_GL1) || ((IT) == DMA1_IT_TC1) || \
+ ((IT) == DMA1_IT_HT1) || ((IT) == DMA1_IT_TE1) || \
+ ((IT) == DMA1_IT_GL2) || ((IT) == DMA1_IT_TC2) || \
+ ((IT) == DMA1_IT_HT2) || ((IT) == DMA1_IT_TE2) || \
+ ((IT) == DMA1_IT_GL3) || ((IT) == DMA1_IT_TC3) || \
+ ((IT) == DMA1_IT_HT3) || ((IT) == DMA1_IT_TE3) || \
+ ((IT) == DMA1_IT_GL4) || ((IT) == DMA1_IT_TC4) || \
+ ((IT) == DMA1_IT_HT4) || ((IT) == DMA1_IT_TE4) || \
+ ((IT) == DMA1_IT_GL5) || ((IT) == DMA1_IT_TC5) || \
+ ((IT) == DMA1_IT_HT5) || ((IT) == DMA1_IT_TE5) || \
+ ((IT) == DMA1_IT_GL6) || ((IT) == DMA1_IT_TC6) || \
+ ((IT) == DMA1_IT_HT6) || ((IT) == DMA1_IT_TE6) || \
+ ((IT) == DMA1_IT_GL7) || ((IT) == DMA1_IT_TC7) || \
+ ((IT) == DMA1_IT_HT7) || ((IT) == DMA1_IT_TE7) || \
+ ((IT) == DMA2_IT_GL1) || ((IT) == DMA2_IT_TC1) || \
+ ((IT) == DMA2_IT_HT1) || ((IT) == DMA2_IT_TE1) || \
+ ((IT) == DMA2_IT_GL2) || ((IT) == DMA2_IT_TC2) || \
+ ((IT) == DMA2_IT_HT2) || ((IT) == DMA2_IT_TE2) || \
+ ((IT) == DMA2_IT_GL3) || ((IT) == DMA2_IT_TC3) || \
+ ((IT) == DMA2_IT_HT3) || ((IT) == DMA2_IT_TE3) || \
+ ((IT) == DMA2_IT_GL4) || ((IT) == DMA2_IT_TC4) || \
+ ((IT) == DMA2_IT_HT4) || ((IT) == DMA2_IT_TE4) || \
+ ((IT) == DMA2_IT_GL5) || ((IT) == DMA2_IT_TC5) || \
+ ((IT) == DMA2_IT_HT5) || ((IT) == DMA2_IT_TE5))
+
+/* DMA flags definition ------------------------------------------------------*/
+/* For DMA1 */
+#define DMA1_FLAG_GL1 ((u32)0x00000001)
+#define DMA1_FLAG_TC1 ((u32)0x00000002)
+#define DMA1_FLAG_HT1 ((u32)0x00000004)
+#define DMA1_FLAG_TE1 ((u32)0x00000008)
+#define DMA1_FLAG_GL2 ((u32)0x00000010)
+#define DMA1_FLAG_TC2 ((u32)0x00000020)
+#define DMA1_FLAG_HT2 ((u32)0x00000040)
+#define DMA1_FLAG_TE2 ((u32)0x00000080)
+#define DMA1_FLAG_GL3 ((u32)0x00000100)
+#define DMA1_FLAG_TC3 ((u32)0x00000200)
+#define DMA1_FLAG_HT3 ((u32)0x00000400)
+#define DMA1_FLAG_TE3 ((u32)0x00000800)
+#define DMA1_FLAG_GL4 ((u32)0x00001000)
+#define DMA1_FLAG_TC4 ((u32)0x00002000)
+#define DMA1_FLAG_HT4 ((u32)0x00004000)
+#define DMA1_FLAG_TE4 ((u32)0x00008000)
+#define DMA1_FLAG_GL5 ((u32)0x00010000)
+#define DMA1_FLAG_TC5 ((u32)0x00020000)
+#define DMA1_FLAG_HT5 ((u32)0x00040000)
+#define DMA1_FLAG_TE5 ((u32)0x00080000)
+#define DMA1_FLAG_GL6 ((u32)0x00100000)
+#define DMA1_FLAG_TC6 ((u32)0x00200000)
+#define DMA1_FLAG_HT6 ((u32)0x00400000)
+#define DMA1_FLAG_TE6 ((u32)0x00800000)
+#define DMA1_FLAG_GL7 ((u32)0x01000000)
+#define DMA1_FLAG_TC7 ((u32)0x02000000)
+#define DMA1_FLAG_HT7 ((u32)0x04000000)
+#define DMA1_FLAG_TE7 ((u32)0x08000000)
+/* For DMA2 */
+#define DMA2_FLAG_GL1 ((u32)0x10000001)
+#define DMA2_FLAG_TC1 ((u32)0x10000002)
+#define DMA2_FLAG_HT1 ((u32)0x10000004)
+#define DMA2_FLAG_TE1 ((u32)0x10000008)
+#define DMA2_FLAG_GL2 ((u32)0x10000010)
+#define DMA2_FLAG_TC2 ((u32)0x10000020)
+#define DMA2_FLAG_HT2 ((u32)0x10000040)
+#define DMA2_FLAG_TE2 ((u32)0x10000080)
+#define DMA2_FLAG_GL3 ((u32)0x10000100)
+#define DMA2_FLAG_TC3 ((u32)0x10000200)
+#define DMA2_FLAG_HT3 ((u32)0x10000400)
+#define DMA2_FLAG_TE3 ((u32)0x10000800)
+#define DMA2_FLAG_GL4 ((u32)0x10001000)
+#define DMA2_FLAG_TC4 ((u32)0x10002000)
+#define DMA2_FLAG_HT4 ((u32)0x10004000)
+#define DMA2_FLAG_TE4 ((u32)0x10008000)
+#define DMA2_FLAG_GL5 ((u32)0x10010000)
+#define DMA2_FLAG_TC5 ((u32)0x10020000)
+#define DMA2_FLAG_HT5 ((u32)0x10040000)
+#define DMA2_FLAG_TE5 ((u32)0x10080000)
+
+#define IS_DMA_CLEAR_FLAG(FLAG) (((((FLAG) & 0xF0000000) == 0x00) || (((FLAG) & 0xEFF00000) == 0x00)) && ((FLAG) != 0x00))
+#define IS_DMA_GET_FLAG(FLAG) (((FLAG) == DMA1_FLAG_GL1) || ((FLAG) == DMA1_FLAG_TC1) || \
+ ((FLAG) == DMA1_FLAG_HT1) || ((FLAG) == DMA1_FLAG_TE1) || \
+ ((FLAG) == DMA1_FLAG_GL2) || ((FLAG) == DMA1_FLAG_TC2) || \
+ ((FLAG) == DMA1_FLAG_HT2) || ((FLAG) == DMA1_FLAG_TE2) || \
+ ((FLAG) == DMA1_FLAG_GL3) || ((FLAG) == DMA1_FLAG_TC3) || \
+ ((FLAG) == DMA1_FLAG_HT3) || ((FLAG) == DMA1_FLAG_TE3) || \
+ ((FLAG) == DMA1_FLAG_GL4) || ((FLAG) == DMA1_FLAG_TC4) || \
+ ((FLAG) == DMA1_FLAG_HT4) || ((FLAG) == DMA1_FLAG_TE4) || \
+ ((FLAG) == DMA1_FLAG_GL5) || ((FLAG) == DMA1_FLAG_TC5) || \
+ ((FLAG) == DMA1_FLAG_HT5) || ((FLAG) == DMA1_FLAG_TE5) || \
+ ((FLAG) == DMA1_FLAG_GL6) || ((FLAG) == DMA1_FLAG_TC6) || \
+ ((FLAG) == DMA1_FLAG_HT6) || ((FLAG) == DMA1_FLAG_TE6) || \
+ ((FLAG) == DMA1_FLAG_GL7) || ((FLAG) == DMA1_FLAG_TC7) || \
+ ((FLAG) == DMA1_FLAG_HT7) || ((FLAG) == DMA1_FLAG_TE7) || \
+ ((FLAG) == DMA2_FLAG_GL1) || ((FLAG) == DMA2_FLAG_TC1) || \
+ ((FLAG) == DMA2_FLAG_HT1) || ((FLAG) == DMA2_FLAG_TE1) || \
+ ((FLAG) == DMA2_FLAG_GL2) || ((FLAG) == DMA2_FLAG_TC2) || \
+ ((FLAG) == DMA2_FLAG_HT2) || ((FLAG) == DMA2_FLAG_TE2) || \
+ ((FLAG) == DMA2_FLAG_GL3) || ((FLAG) == DMA2_FLAG_TC3) || \
+ ((FLAG) == DMA2_FLAG_HT3) || ((FLAG) == DMA2_FLAG_TE3) || \
+ ((FLAG) == DMA2_FLAG_GL4) || ((FLAG) == DMA2_FLAG_TC4) || \
+ ((FLAG) == DMA2_FLAG_HT4) || ((FLAG) == DMA2_FLAG_TE4) || \
+ ((FLAG) == DMA2_FLAG_GL5) || ((FLAG) == DMA2_FLAG_TC5) || \
+ ((FLAG) == DMA2_FLAG_HT5) || ((FLAG) == DMA2_FLAG_TE5))
+
+/* DMA Buffer Size -----------------------------------------------------------*/
+#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x1) && ((SIZE) < 0x10000))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx);
+void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct);
+void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct);
+void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState);
+void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, u32 DMA_IT, FunctionalState NewState);
+u16 DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx);
+FlagStatus DMA_GetFlagStatus(u32 DMA_FLAG);
+void DMA_ClearFlag(u32 DMA_FLAG);
+ITStatus DMA_GetITStatus(u32 DMA_IT);
+void DMA_ClearITPendingBit(u32 DMA_IT);
+
+#endif /*__STM32F10x_DMA_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_exti.h b/src/stm32lib/inc/stm32f10x_exti.h new file mode 100644 index 0000000..46ac68d --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_exti.h @@ -0,0 +1,113 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_exti.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* EXTI firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_EXTI_H
+#define __STM32F10x_EXTI_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* EXTI mode enumeration -----------------------------------------------------*/
+typedef enum
+{
+ EXTI_Mode_Interrupt = 0x00,
+ EXTI_Mode_Event = 0x04
+}EXTIMode_TypeDef;
+
+#define IS_EXTI_MODE(MODE) (((MODE) == EXTI_Mode_Interrupt) || ((MODE) == EXTI_Mode_Event))
+
+/* EXTI Trigger enumeration --------------------------------------------------*/
+typedef enum
+{
+ EXTI_Trigger_Rising = 0x08,
+ EXTI_Trigger_Falling = 0x0C,
+ EXTI_Trigger_Rising_Falling = 0x10
+}EXTITrigger_TypeDef;
+
+#define IS_EXTI_TRIGGER(TRIGGER) (((TRIGGER) == EXTI_Trigger_Rising) || \
+ ((TRIGGER) == EXTI_Trigger_Falling) || \
+ ((TRIGGER) == EXTI_Trigger_Rising_Falling))
+
+/* EXTI Init Structure definition --------------------------------------------*/
+typedef struct
+{
+ u32 EXTI_Line;
+ EXTIMode_TypeDef EXTI_Mode;
+ EXTITrigger_TypeDef EXTI_Trigger;
+ FunctionalState EXTI_LineCmd;
+}EXTI_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+/* EXTI Lines ----------------------------------------------------------------*/
+#define EXTI_Line0 ((u32)0x00001) /* External interrupt line 0 */
+#define EXTI_Line1 ((u32)0x00002) /* External interrupt line 1 */
+#define EXTI_Line2 ((u32)0x00004) /* External interrupt line 2 */
+#define EXTI_Line3 ((u32)0x00008) /* External interrupt line 3 */
+#define EXTI_Line4 ((u32)0x00010) /* External interrupt line 4 */
+#define EXTI_Line5 ((u32)0x00020) /* External interrupt line 5 */
+#define EXTI_Line6 ((u32)0x00040) /* External interrupt line 6 */
+#define EXTI_Line7 ((u32)0x00080) /* External interrupt line 7 */
+#define EXTI_Line8 ((u32)0x00100) /* External interrupt line 8 */
+#define EXTI_Line9 ((u32)0x00200) /* External interrupt line 9 */
+#define EXTI_Line10 ((u32)0x00400) /* External interrupt line 10 */
+#define EXTI_Line11 ((u32)0x00800) /* External interrupt line 11 */
+#define EXTI_Line12 ((u32)0x01000) /* External interrupt line 12 */
+#define EXTI_Line13 ((u32)0x02000) /* External interrupt line 13 */
+#define EXTI_Line14 ((u32)0x04000) /* External interrupt line 14 */
+#define EXTI_Line15 ((u32)0x08000) /* External interrupt line 15 */
+#define EXTI_Line16 ((u32)0x10000) /* External interrupt line 16
+ Connected to the PVD Output */
+#define EXTI_Line17 ((u32)0x20000) /* External interrupt line 17
+ Connected to the RTC Alarm event */
+#define EXTI_Line18 ((u32)0x40000) /* External interrupt line 18
+ Connected to the USB Wakeup from
+ suspend event */
+
+#define IS_EXTI_LINE(LINE) ((((LINE) & (u32)0xFFF80000) == 0x00) && ((LINE) != (u16)0x00))
+
+#define IS_GET_EXTI_LINE(LINE) (((LINE) == EXTI_Line0) || ((LINE) == EXTI_Line1) || \
+ ((LINE) == EXTI_Line2) || ((LINE) == EXTI_Line3) || \
+ ((LINE) == EXTI_Line4) || ((LINE) == EXTI_Line5) || \
+ ((LINE) == EXTI_Line6) || ((LINE) == EXTI_Line7) || \
+ ((LINE) == EXTI_Line8) || ((LINE) == EXTI_Line9) || \
+ ((LINE) == EXTI_Line10) || ((LINE) == EXTI_Line11) || \
+ ((LINE) == EXTI_Line12) || ((LINE) == EXTI_Line13) || \
+ ((LINE) == EXTI_Line14) || ((LINE) == EXTI_Line15) || \
+ ((LINE) == EXTI_Line16) || ((LINE) == EXTI_Line17) || \
+ ((LINE) == EXTI_Line18))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+#ifdef __cplusplus
+extern "C" {
+#endif
+void EXTI_DeInit(void);
+void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct);
+void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct);
+void EXTI_GenerateSWInterrupt(u32 EXTI_Line);
+FlagStatus EXTI_GetFlagStatus(u32 EXTI_Line);
+void EXTI_ClearFlag(u32 EXTI_Line);
+ITStatus EXTI_GetITStatus(u32 EXTI_Line);
+void EXTI_ClearITPendingBit(u32 EXTI_Line);
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_EXTI_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_flash.h b/src/stm32lib/inc/stm32f10x_flash.h new file mode 100644 index 0000000..459a044 --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_flash.h @@ -0,0 +1,215 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_flash.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* FLASH firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_FLASH_H
+#define __STM32F10x_FLASH_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+
+/* Exported types ------------------------------------------------------------*/
+#ifdef _FLASH_PROG
+/* FLASH Status */
+typedef enum
+{
+ FLASH_BUSY = 1,
+ FLASH_ERROR_PG,
+ FLASH_ERROR_WRP,
+ FLASH_COMPLETE,
+ FLASH_TIMEOUT
+}FLASH_Status;
+#endif
+
+/* Flash Latency -------------------------------------------------------------*/
+#define FLASH_Latency_0 ((u32)0x00000000) /* FLASH Zero Latency cycle */
+#define FLASH_Latency_1 ((u32)0x00000001) /* FLASH One Latency cycle */
+#define FLASH_Latency_2 ((u32)0x00000002) /* FLASH Two Latency cycles */
+
+#define IS_FLASH_LATENCY(LATENCY) (((LATENCY) == FLASH_Latency_0) || \
+ ((LATENCY) == FLASH_Latency_1) || \
+ ((LATENCY) == FLASH_Latency_2))
+
+/* Half Cycle Enable/Disable -------------------------------------------------*/
+#define FLASH_HalfCycleAccess_Enable ((u32)0x00000008) /* FLASH Half Cycle Enable */
+#define FLASH_HalfCycleAccess_Disable ((u32)0x00000000) /* FLASH Half Cycle Disable */
+
+#define IS_FLASH_HALFCYCLEACCESS_STATE(STATE) (((STATE) == FLASH_HalfCycleAccess_Enable) || \
+ ((STATE) == FLASH_HalfCycleAccess_Disable))
+
+
+/* Prefetch Buffer Enable/Disable --------------------------------------------*/
+#define FLASH_PrefetchBuffer_Enable ((u32)0x00000010) /* FLASH Prefetch Buffer Enable */
+#define FLASH_PrefetchBuffer_Disable ((u32)0x00000000) /* FLASH Prefetch Buffer Disable */
+
+#define IS_FLASH_PREFETCHBUFFER_STATE(STATE) (((STATE) == FLASH_PrefetchBuffer_Enable) || \
+ ((STATE) == FLASH_PrefetchBuffer_Disable))
+
+#ifdef _FLASH_PROG
+/* Option Bytes Write Protection ---------------------------------------------*/
+/* Values to be used with STM32F10Xxx Medium-density devices: FLASH memory density
+ ranges between 32 and 128 Kbytes with page size equal to 1 Kbytes */
+#define FLASH_WRProt_Pages0to3 ((u32)0x00000001) /* Write protection of page 0 to 3 */
+#define FLASH_WRProt_Pages4to7 ((u32)0x00000002) /* Write protection of page 4 to 7 */
+#define FLASH_WRProt_Pages8to11 ((u32)0x00000004) /* Write protection of page 8 to 11 */
+#define FLASH_WRProt_Pages12to15 ((u32)0x00000008) /* Write protection of page 12 to 15 */
+#define FLASH_WRProt_Pages16to19 ((u32)0x00000010) /* Write protection of page 16 to 19 */
+#define FLASH_WRProt_Pages20to23 ((u32)0x00000020) /* Write protection of page 20 to 23 */
+#define FLASH_WRProt_Pages24to27 ((u32)0x00000040) /* Write protection of page 24 to 27 */
+#define FLASH_WRProt_Pages28to31 ((u32)0x00000080) /* Write protection of page 28 to 31 */
+#define FLASH_WRProt_Pages32to35 ((u32)0x00000100) /* Write protection of page 32 to 35 */
+#define FLASH_WRProt_Pages36to39 ((u32)0x00000200) /* Write protection of page 36 to 39 */
+#define FLASH_WRProt_Pages40to43 ((u32)0x00000400) /* Write protection of page 40 to 43 */
+#define FLASH_WRProt_Pages44to47 ((u32)0x00000800) /* Write protection of page 44 to 47 */
+#define FLASH_WRProt_Pages48to51 ((u32)0x00001000) /* Write protection of page 48 to 51 */
+#define FLASH_WRProt_Pages52to55 ((u32)0x00002000) /* Write protection of page 52 to 55 */
+#define FLASH_WRProt_Pages56to59 ((u32)0x00004000) /* Write protection of page 56 to 59 */
+#define FLASH_WRProt_Pages60to63 ((u32)0x00008000) /* Write protection of page 60 to 63 */
+#define FLASH_WRProt_Pages64to67 ((u32)0x00010000) /* Write protection of page 64 to 67 */
+#define FLASH_WRProt_Pages68to71 ((u32)0x00020000) /* Write protection of page 68 to 71 */
+#define FLASH_WRProt_Pages72to75 ((u32)0x00040000) /* Write protection of page 72 to 75 */
+#define FLASH_WRProt_Pages76to79 ((u32)0x00080000) /* Write protection of page 76 to 79 */
+#define FLASH_WRProt_Pages80to83 ((u32)0x00100000) /* Write protection of page 80 to 83 */
+#define FLASH_WRProt_Pages84to87 ((u32)0x00200000) /* Write protection of page 84 to 87 */
+#define FLASH_WRProt_Pages88to91 ((u32)0x00400000) /* Write protection of page 88 to 91 */
+#define FLASH_WRProt_Pages92to95 ((u32)0x00800000) /* Write protection of page 92 to 95 */
+#define FLASH_WRProt_Pages96to99 ((u32)0x01000000) /* Write protection of page 96 to 99 */
+#define FLASH_WRProt_Pages100to103 ((u32)0x02000000) /* Write protection of page 100 to 103 */
+#define FLASH_WRProt_Pages104to107 ((u32)0x04000000) /* Write protection of page 104 to 107 */
+#define FLASH_WRProt_Pages108to111 ((u32)0x08000000) /* Write protection of page 108 to 111 */
+#define FLASH_WRProt_Pages112to115 ((u32)0x10000000) /* Write protection of page 112 to 115 */
+#define FLASH_WRProt_Pages116to119 ((u32)0x20000000) /* Write protection of page 115 to 119 */
+#define FLASH_WRProt_Pages120to123 ((u32)0x40000000) /* Write protection of page 120 to 123 */
+#define FLASH_WRProt_Pages124to127 ((u32)0x80000000) /* Write protection of page 124 to 127 */
+/* Values to be used with STM32F10Xxx High-density devices: FLASH memory density
+ ranges between 256 and 512 Kbytes with page size equal to 2 Kbytes */
+#define FLASH_WRProt_Pages0to1 ((u32)0x00000001) /* Write protection of page 0 to 1 */
+#define FLASH_WRProt_Pages2to3 ((u32)0x00000002) /* Write protection of page 2 to 3 */
+#define FLASH_WRProt_Pages4to5 ((u32)0x00000004) /* Write protection of page 4 to 5 */
+#define FLASH_WRProt_Pages6to7 ((u32)0x00000008) /* Write protection of page 6 to 7 */
+#define FLASH_WRProt_Pages8to9 ((u32)0x00000010) /* Write protection of page 8 to 9 */
+#define FLASH_WRProt_Pages10to11 ((u32)0x00000020) /* Write protection of page 10 to 11 */
+#define FLASH_WRProt_Pages12to13 ((u32)0x00000040) /* Write protection of page 12 to 13 */
+#define FLASH_WRProt_Pages14to15 ((u32)0x00000080) /* Write protection of page 14 to 15 */
+#define FLASH_WRProt_Pages16to17 ((u32)0x00000100) /* Write protection of page 16 to 17 */
+#define FLASH_WRProt_Pages18to19 ((u32)0x00000200) /* Write protection of page 18 to 19 */
+#define FLASH_WRProt_Pages20to21 ((u32)0x00000400) /* Write protection of page 20 to 21 */
+#define FLASH_WRProt_Pages22to23 ((u32)0x00000800) /* Write protection of page 22 to 23 */
+#define FLASH_WRProt_Pages24to25 ((u32)0x00001000) /* Write protection of page 24 to 25 */
+#define FLASH_WRProt_Pages26to27 ((u32)0x00002000) /* Write protection of page 26 to 27 */
+#define FLASH_WRProt_Pages28to29 ((u32)0x00004000) /* Write protection of page 28 to 29 */
+#define FLASH_WRProt_Pages30to31 ((u32)0x00008000) /* Write protection of page 30 to 31 */
+#define FLASH_WRProt_Pages32to33 ((u32)0x00010000) /* Write protection of page 32 to 33 */
+#define FLASH_WRProt_Pages34to35 ((u32)0x00020000) /* Write protection of page 34 to 35 */
+#define FLASH_WRProt_Pages36to37 ((u32)0x00040000) /* Write protection of page 36 to 37 */
+#define FLASH_WRProt_Pages38to39 ((u32)0x00080000) /* Write protection of page 38 to 39 */
+#define FLASH_WRProt_Pages40to41 ((u32)0x00100000) /* Write protection of page 40 to 41 */
+#define FLASH_WRProt_Pages42to43 ((u32)0x00200000) /* Write protection of page 42 to 43 */
+#define FLASH_WRProt_Pages44to45 ((u32)0x00400000) /* Write protection of page 44 to 45 */
+#define FLASH_WRProt_Pages46to47 ((u32)0x00800000) /* Write protection of page 46 to 47 */
+#define FLASH_WRProt_Pages48to49 ((u32)0x01000000) /* Write protection of page 48 to 49 */
+#define FLASH_WRProt_Pages50to51 ((u32)0x02000000) /* Write protection of page 50 to 51 */
+#define FLASH_WRProt_Pages52to53 ((u32)0x04000000) /* Write protection of page 52 to 53 */
+#define FLASH_WRProt_Pages54to55 ((u32)0x08000000) /* Write protection of page 54 to 55 */
+#define FLASH_WRProt_Pages56to57 ((u32)0x10000000) /* Write protection of page 56 to 57 */
+#define FLASH_WRProt_Pages58to59 ((u32)0x20000000) /* Write protection of page 58 to 59 */
+#define FLASH_WRProt_Pages60to61 ((u32)0x40000000) /* Write protection of page 60 to 61 */
+#define FLASH_WRProt_Pages62to255 ((u32)0x80000000) /* Write protection of page 62 to 255 */
+#define FLASH_WRProt_AllPages ((u32)0xFFFFFFFF) /* Write protection of all Pages */
+
+#define IS_FLASH_WRPROT_PAGE(PAGE) (((PAGE) != 0x00000000))
+
+#define IS_FLASH_ADDRESS(ADDRESS) (((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x0807FFFF))
+#define IS_OB_DATA_ADDRESS(ADDRESS) (((ADDRESS) == 0x1FFFF804) || ((ADDRESS) == 0x1FFFF806))
+
+/* Option Bytes IWatchdog ----------------------------------------------------*/
+#define OB_IWDG_SW ((u16)0x0001) /* Software IWDG selected */
+#define OB_IWDG_HW ((u16)0x0000) /* Hardware IWDG selected */
+
+#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW))
+
+/* Option Bytes nRST_STOP ----------------------------------------------------*/
+#define OB_STOP_NoRST ((u16)0x0002) /* No reset generated when entering in STOP */
+#define OB_STOP_RST ((u16)0x0000) /* Reset generated when entering in STOP */
+
+#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NoRST) || ((SOURCE) == OB_STOP_RST))
+
+/* Option Bytes nRST_STDBY ---------------------------------------------------*/
+#define OB_STDBY_NoRST ((u16)0x0004) /* No reset generated when entering in STANDBY */
+#define OB_STDBY_RST ((u16)0x0000) /* Reset generated when entering in STANDBY */
+
+#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NoRST) || ((SOURCE) == OB_STDBY_RST))
+
+/* FLASH Interrupts ----------------------------------------------------------*/
+#define FLASH_IT_ERROR ((u32)0x00000400) /* FPEC error interrupt source */
+#define FLASH_IT_EOP ((u32)0x00001000) /* End of FLASH Operation Interrupt source */
+
+#define IS_FLASH_IT(IT) ((((IT) & (u32)0xFFFFEBFF) == 0x00000000) && (((IT) != 0x00000000)))
+
+/* FLASH Flags ---------------------------------------------------------------*/
+#define FLASH_FLAG_BSY ((u32)0x00000001) /* FLASH Busy flag */
+#define FLASH_FLAG_EOP ((u32)0x00000020) /* FLASH End of Operation flag */
+#define FLASH_FLAG_PGERR ((u32)0x00000004) /* FLASH Program error flag */
+#define FLASH_FLAG_WRPRTERR ((u32)0x00000010) /* FLASH Write protected error flag */
+#define FLASH_FLAG_OPTERR ((u32)0x00000001) /* FLASH Option Byte error flag */
+
+#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (u32)0xFFFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000))
+
+#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \
+ ((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \
+ ((FLAG) == FLASH_FLAG_OPTERR))
+#endif
+
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+#ifdef __cplusplus
+extern "C" {
+#endif
+void FLASH_SetLatency(u32 FLASH_Latency);
+void FLASH_HalfCycleAccessCmd(u32 FLASH_HalfCycleAccess);
+void FLASH_PrefetchBufferCmd(u32 FLASH_PrefetchBuffer);
+#ifdef __cplusplus
+};
+#endif
+
+#ifdef _FLASH_PROG
+void FLASH_Unlock(void);
+void FLASH_Lock(void);
+FLASH_Status FLASH_ErasePage(u32 Page_Address);
+FLASH_Status FLASH_EraseAllPages(void);
+FLASH_Status FLASH_EraseOptionBytes(void);
+FLASH_Status FLASH_ProgramWord(u32 Address, u32 Data);
+FLASH_Status FLASH_ProgramHalfWord(u32 Address, u16 Data);
+FLASH_Status FLASH_ProgramOptionByteData(u32 Address, u8 Data);
+FLASH_Status FLASH_EnableWriteProtection(u32 FLASH_Pages);
+FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState);
+FLASH_Status FLASH_UserOptionByteConfig(u16 OB_IWDG, u16 OB_STOP, u16 OB_STDBY);
+u32 FLASH_GetUserOptionByte(void);
+u32 FLASH_GetWriteProtectionOptionByte(void);
+FlagStatus FLASH_GetReadOutProtectionStatus(void);
+FlagStatus FLASH_GetPrefetchBufferStatus(void);
+void FLASH_ITConfig(u16 FLASH_IT, FunctionalState NewState);
+FlagStatus FLASH_GetFlagStatus(u16 FLASH_FLAG);
+void FLASH_ClearFlag(u16 FLASH_FLAG);
+FLASH_Status FLASH_GetStatus(void);
+FLASH_Status FLASH_WaitForLastOperation(u32 Timeout);
+#endif
+
+#endif /* __STM32F10x_FLASH_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_fsmc.h b/src/stm32lib/inc/stm32f10x_fsmc.h new file mode 100644 index 0000000..d508299 --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_fsmc.h @@ -0,0 +1,355 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_fsmc.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* FSMC firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_FSMC_H
+#define __STM32F10x_FSMC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Timing parameters For NOR/SRAM Banks */
+typedef struct
+{
+ u32 FSMC_AddressSetupTime;
+ u32 FSMC_AddressHoldTime;
+ u32 FSMC_DataSetupTime;
+ u32 FSMC_BusTurnAroundDuration;
+ u32 FSMC_CLKDivision;
+ u32 FSMC_DataLatency;
+ u32 FSMC_AccessMode;
+}FSMC_NORSRAMTimingInitTypeDef;
+
+/* FSMC NOR/SRAM Init structure definition */
+typedef struct
+{
+ u32 FSMC_Bank;
+ u32 FSMC_DataAddressMux;
+ u32 FSMC_MemoryType;
+ u32 FSMC_MemoryDataWidth;
+ u32 FSMC_BurstAccessMode;
+ u32 FSMC_WaitSignalPolarity;
+ u32 FSMC_WrapMode;
+ u32 FSMC_WaitSignalActive;
+ u32 FSMC_WriteOperation;
+ u32 FSMC_WaitSignal;
+ u32 FSMC_ExtendedMode;
+ u32 FSMC_AsyncWait;
+ u32 FSMC_WriteBurst;
+ /* Timing Parameters for write and read access if the ExtendedMode is not used*/
+ FSMC_NORSRAMTimingInitTypeDef* FSMC_ReadWriteTimingStruct;
+ /* Timing Parameters for write access if the ExtendedMode is used*/
+ FSMC_NORSRAMTimingInitTypeDef* FSMC_WriteTimingStruct;
+}FSMC_NORSRAMInitTypeDef;
+
+/* Timing parameters For FSMC NAND and PCCARD Banks */
+typedef struct
+{
+ u32 FSMC_SetupTime;
+ u32 FSMC_WaitSetupTime;
+ u32 FSMC_HoldSetupTime;
+ u32 FSMC_HiZSetupTime;
+}FSMC_NAND_PCCARDTimingInitTypeDef;
+
+/* FSMC NAND Init structure definition */
+typedef struct
+{
+ u32 FSMC_Bank;
+ u32 FSMC_Waitfeature;
+ u32 FSMC_MemoryDataWidth;
+ u32 FSMC_ECC;
+ u32 FSMC_ECCPageSize;
+ u32 FSMC_AddressLowMapping;
+ u32 FSMC_TCLRSetupTime;
+ u32 FSMC_TARSetupTime;
+ /* FSMC Common Space Timing */
+ FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct;
+ /* FSMC Attribute Space Timing */
+ FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct;
+}FSMC_NANDInitTypeDef;
+
+/* FSMC PCCARD Init structure definition */
+typedef struct
+{
+ u32 FSMC_Waitfeature;
+ u32 FSMC_AddressLowMapping;
+ u32 FSMC_TCLRSetupTime;
+ u32 FSMC_TARSetupTime;
+ /* FSMC Common Space Timing */
+ FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct;
+ /* FSMC Attribute Space Timing */
+ FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct;
+ /* FSMC IO Space Timing */
+ FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_IOSpaceTimingStruct;
+}FSMC_PCCARDInitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+/*-------------------------------FSMC Banks definitions ----------------------*/
+#define FSMC_Bank1_NORSRAM1 ((u32)0x00000000)
+#define FSMC_Bank1_NORSRAM2 ((u32)0x00000002)
+#define FSMC_Bank1_NORSRAM3 ((u32)0x00000004)
+#define FSMC_Bank1_NORSRAM4 ((u32)0x00000006)
+#define FSMC_Bank2_NAND ((u32)0x00000010)
+#define FSMC_Bank3_NAND ((u32)0x00000100)
+#define FSMC_Bank4_PCCARD ((u32)0x00001000)
+
+#define IS_FSMC_NORSRAM_BANK(BANK) (((BANK) == FSMC_Bank1_NORSRAM1) || \
+ ((BANK) == FSMC_Bank1_NORSRAM2) || \
+ ((BANK) == FSMC_Bank1_NORSRAM3) || \
+ ((BANK) == FSMC_Bank1_NORSRAM4))
+
+
+#define IS_FSMC_NAND_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
+ ((BANK) == FSMC_Bank3_NAND))
+
+#define IS_FSMC_GETFLAG_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
+ ((BANK) == FSMC_Bank3_NAND) || \
+ ((BANK) == FSMC_Bank4_PCCARD))
+
+#define IS_FSMC_IT_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
+ ((BANK) == FSMC_Bank3_NAND) || \
+ ((BANK) == FSMC_Bank4_PCCARD))
+
+
+/*------------------------------- NOR/SRAM Banks -----------------------------*/
+/* FSMC Data/Address Bus Multiplexing ----------------------------------------*/
+#define FSMC_DataAddressMux_Disable ((u32)0x00000000)
+#define FSMC_DataAddressMux_Enable ((u32)0x00000002)
+
+#define IS_FSMC_MUX(MUX) (((MUX) == FSMC_DataAddressMux_Disable) || \
+ ((MUX) == FSMC_DataAddressMux_Enable))
+
+/* FSMC Memory Type ----------------------------------------------------------*/
+#define FSMC_MemoryType_SRAM ((u32)0x00000000)
+#define FSMC_MemoryType_CRAM ((u32)0x00000004)
+#define FSMC_MemoryType_NOR ((u32)0x00000008)
+#define FSMC_MemoryType_COSMORAM ((u32)0x0000000C)
+
+#define IS_FSMC_MEMORY(MEMORY) (((MEMORY) == FSMC_MemoryType_SRAM) || \
+ ((MEMORY) == FSMC_MemoryType_CRAM)|| \
+ ((MEMORY) == FSMC_MemoryType_NOR)|| \
+ ((MEMORY) == FSMC_MemoryType_COSMORAM))
+
+/* FSMC Data Width ----------------------------------------------------------*/
+#define FSMC_MemoryDataWidth_8b ((u32)0x00000000)
+#define FSMC_MemoryDataWidth_16b ((u32)0x00000010)
+
+#define IS_FSMC_MEMORY_WIDTH(WIDTH) (((WIDTH) == FSMC_MemoryDataWidth_8b) || \
+ ((WIDTH) == FSMC_MemoryDataWidth_16b))
+
+
+/* FSMC Burst Access Mode ----------------------------------------------------*/
+#define FSMC_BurstAccessMode_Disable ((u32)0x00000000)
+#define FSMC_BurstAccessMode_Enable ((u32)0x00000100)
+
+#define IS_FSMC_BURSTMODE(STATE) (((STATE) == FSMC_BurstAccessMode_Disable) || \
+ ((STATE) == FSMC_BurstAccessMode_Enable))
+
+/* FSMC Wait Signal Polarity -------------------------------------------------*/
+#define FSMC_WaitSignalPolarity_Low ((u32)0x00000000)
+#define FSMC_WaitSignalPolarity_High ((u32)0x00000200)
+
+#define IS_FSMC_WAIT_POLARITY(POLARITY) (((POLARITY) == FSMC_WaitSignalPolarity_Low) || \
+ ((POLARITY) == FSMC_WaitSignalPolarity_High))
+
+/* FSMC Wrap Mode ------------------------------------------------------------*/
+#define FSMC_WrapMode_Disable ((u32)0x00000000)
+#define FSMC_WrapMode_Enable ((u32)0x00000400)
+
+#define IS_FSMC_WRAP_MODE(MODE) (((MODE) == FSMC_WrapMode_Disable) || \
+ ((MODE) == FSMC_WrapMode_Enable))
+
+/* FSMC Wait Timing ----------------------------------------------------------*/
+#define FSMC_WaitSignalActive_BeforeWaitState ((u32)0x00000000)
+#define FSMC_WaitSignalActive_DuringWaitState ((u32)0x00000800)
+
+#define IS_FSMC_WAIT_SIGNAL_ACTIVE(ACTIVE) (((ACTIVE) == FSMC_WaitSignalActive_BeforeWaitState) || \
+ ((ACTIVE) == FSMC_WaitSignalActive_DuringWaitState))
+
+/* FSMC Write Operation ------------------------------------------------------*/
+#define FSMC_WriteOperation_Disable ((u32)0x00000000)
+#define FSMC_WriteOperation_Enable ((u32)0x00001000)
+
+#define IS_FSMC_WRITE_OPERATION(OPERATION) (((OPERATION) == FSMC_WriteOperation_Disable) || \
+ ((OPERATION) == FSMC_WriteOperation_Enable))
+
+/* FSMC Wait Signal ----------------------------------------------------------*/
+#define FSMC_WaitSignal_Disable ((u32)0x00000000)
+#define FSMC_WaitSignal_Enable ((u32)0x00002000)
+
+#define IS_FSMC_WAITE_SIGNAL(SIGNAL) (((SIGNAL) == FSMC_WaitSignal_Disable) || \
+ ((SIGNAL) == FSMC_WaitSignal_Enable))
+
+/* FSMC Extended Mode --------------------------------------------------------*/
+#define FSMC_ExtendedMode_Disable ((u32)0x00000000)
+#define FSMC_ExtendedMode_Enable ((u32)0x00004000)
+
+#define IS_FSMC_EXTENDED_MODE(MODE) (((MODE) == FSMC_ExtendedMode_Disable) || \
+ ((MODE) == FSMC_ExtendedMode_Enable))
+
+/* FSMC Asynchronous Wait ----------------------------------------------------*/
+#define FSMC_AsyncWait_Disable ((u32)0x00000000)
+#define FSMC_AsyncWait_Enable ((u32)0x00008000)
+
+#define IS_FSMC_ASYNC_WAIT(WAIT) (((WAIT) == FSMC_AsyncWait_Disable) || \
+ ((WAIT) == FSMC_AsyncWait_Enable))
+
+/* FSMC Write Burst ----------------------------------------------------------*/
+#define FSMC_WriteBurst_Disable ((u32)0x00000000)
+#define FSMC_WriteBurst_Enable ((u32)0x00080000)
+
+#define IS_FSMC_WRITE_BURST(BURST) (((BURST) == FSMC_WriteBurst_Disable) || \
+ ((BURST) == FSMC_WriteBurst_Enable))
+
+/* FSMC Address Setup Time ---------------------------------------------------*/
+#define IS_FSMC_ADDRESS_SETUP_TIME(TIME) ((TIME) <= 0xF)
+
+/* FSMC Address Hold Time ----------------------------------------------------*/
+#define IS_FSMC_ADDRESS_HOLD_TIME(TIME) ((TIME) <= 0xF)
+
+/* FSMC Data Setup Time ------------------------------------------------------*/
+#define IS_FSMC_DATASETUP_TIME(TIME) (((TIME) > 0) && ((TIME) <= 0xFF))
+
+/* FSMC Bus Turn around Duration ---------------------------------------------*/
+#define IS_FSMC_TURNAROUND_TIME(TIME) ((TIME) <= 0xF)
+
+/* FSMC CLK Division ---------------------------------------------------------*/
+#define IS_FSMC_CLK_DIV(DIV) ((DIV) <= 0xF)
+
+/* FSMC Data Latency ---------------------------------------------------------*/
+#define IS_FSMC_DATA_LATENCY(LATENCY) ((LATENCY) <= 0xF)
+
+/* FSMC Access Mode ----------------------------------------------------------*/
+#define FSMC_AccessMode_A ((u32)0x00000000)
+#define FSMC_AccessMode_B ((u32)0x10000000)
+#define FSMC_AccessMode_C ((u32)0x20000000)
+#define FSMC_AccessMode_D ((u32)0x30000000)
+
+#define IS_FSMC_ACCESS_MODE(MODE) (((MODE) == FSMC_AccessMode_A) || \
+ ((MODE) == FSMC_AccessMode_B) || \
+ ((MODE) == FSMC_AccessMode_C) || \
+ ((MODE) == FSMC_AccessMode_D))
+
+/*----------------------------- NAND and PCCARD Banks ------------------------*/
+/* FSMC Wait feature ---------------------------------------------------------*/
+#define FSMC_Waitfeature_Disable ((u32)0x00000000)
+#define FSMC_Waitfeature_Enable ((u32)0x00000002)
+
+#define IS_FSMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FSMC_Waitfeature_Disable) || \
+ ((FEATURE) == FSMC_Waitfeature_Enable))
+
+/* FSMC Memory Data Width ----------------------------------------------------*/
+#define FSMC_MemoryDataWidth_8b ((u32)0x00000000)
+#define FSMC_MemoryDataWidth_16b ((u32)0x00000010)
+
+#define IS_FSMC_DATA_WIDTH(WIDTH) (((WIDTH) == FSMC_MemoryDataWidth_8b) || \
+ ((WIDTH) == FSMC_MemoryDataWidth_16b))
+
+/* FSMC ECC ------------------------------------------------------------------*/
+#define FSMC_ECC_Disable ((u32)0x00000000)
+#define FSMC_ECC_Enable ((u32)0x00000040)
+
+#define IS_FSMC_ECC_STATE(STATE) (((STATE) == FSMC_ECC_Disable) || \
+ ((STATE) == FSMC_ECC_Enable))
+
+/* FSMC ECC Page Size --------------------------------------------------------*/
+#define FSMC_ECCPageSize_256Bytes ((u32)0x00000000)
+#define FSMC_ECCPageSize_512Bytes ((u32)0x00020000)
+#define FSMC_ECCPageSize_1024Bytes ((u32)0x00040000)
+#define FSMC_ECCPageSize_2048Bytes ((u32)0x00060000)
+#define FSMC_ECCPageSize_4096Bytes ((u32)0x00080000)
+#define FSMC_ECCPageSize_8192Bytes ((u32)0x000A0000)
+
+#define IS_FSMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FSMC_ECCPageSize_256Bytes) || \
+ ((SIZE) == FSMC_ECCPageSize_512Bytes) || \
+ ((SIZE) == FSMC_ECCPageSize_1024Bytes) || \
+ ((SIZE) == FSMC_ECCPageSize_2048Bytes) || \
+ ((SIZE) == FSMC_ECCPageSize_4096Bytes) || \
+ ((SIZE) == FSMC_ECCPageSize_8192Bytes))
+
+/* FSMC Address Low Mapping --------------------------------------------------*/
+#define FSMC_AddressLowMapping_Direct ((u32)0x00000000)
+#define FSMC_AddressLowMapping_InDirect ((u32)0x00000100)
+
+#define IS_FSMC_ADDRESS_LOW_MAPPING(MAPPING) (((MAPPING) == FSMC_AddressLowMapping_Direct) || \
+ ((MAPPING) == FSMC_AddressLowMapping_InDirect))
+/* FSMC TCLR Setup Time ------------------------------------------------------*/
+#define IS_FSMC_TCLR_TIME(TIME) ((TIME) <= 0xFF)
+
+/* FSMC TAR Setup Time -------------------------------------------------------*/
+#define IS_FSMC_TAR_TIME(TIME) ((TIME) <= 0xFF)
+
+/* FSMC Setup Time ----------------------------------------------------*/
+#define IS_FSMC_SETUP_TIME(TIME) ((TIME) <= 0xFF)
+
+/* FSMC Wait Setup Time -----------------------------------------------*/
+#define IS_FSMC_WAIT_TIME(TIME) ((TIME) <= 0xFF)
+
+/* FSMC Hold Setup Time -----------------------------------------------*/
+#define IS_FSMC_HOLD_TIME(TIME) ((TIME) <= 0xFF)
+
+/* FSMC HiZ Setup Time ------------------------------------------------*/
+#define IS_FSMC_HIZ_TIME(TIME) ((TIME) <= 0xFF)
+
+/* FSMC Interrupt sources ----------------------------------------------------*/
+#define FSMC_IT_RisingEdge ((u32)0x00000008)
+#define FSMC_IT_Level ((u32)0x00000010)
+#define FSMC_IT_FallingEdge ((u32)0x00000020)
+
+#define IS_FSMC_IT(IT) ((((IT) & (u32)0xFFFFFFC7) == 0x00000000) && ((IT) != 0x00000000))
+
+#define IS_FSMC_GET_IT(IT) (((IT) == FSMC_IT_RisingEdge) || \
+ ((IT) == FSMC_IT_Level) || \
+ ((IT) == FSMC_IT_FallingEdge))
+
+/* FSMC Flags ----------------------------------------------------------------*/
+#define FSMC_FLAG_RisingEdge ((u32)0x00000001)
+#define FSMC_FLAG_Level ((u32)0x00000002)
+#define FSMC_FLAG_FallingEdge ((u32)0x00000004)
+#define FSMC_FLAG_FEMPT ((u32)0x00000040)
+
+#define IS_FSMC_GET_FLAG(FLAG) (((FLAG) == FSMC_FLAG_RisingEdge) || \
+ ((FLAG) == FSMC_FLAG_Level) || \
+ ((FLAG) == FSMC_FLAG_FallingEdge) || \
+ ((FLAG) == FSMC_FLAG_FEMPT))
+
+#define IS_FSMC_CLEAR_FLAG(FLAG) ((((FLAG) & (u32)0xFFFFFFF8) == 0x00000000) && ((FLAG) != 0x00000000))
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void FSMC_NORSRAMDeInit(u32 FSMC_Bank);
+void FSMC_NANDDeInit(u32 FSMC_Bank);
+void FSMC_PCCARDDeInit(void);
+void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct);
+void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct);
+void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct);
+void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct);
+void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct);
+void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct);
+void FSMC_NORSRAMCmd(u32 FSMC_Bank, FunctionalState NewState);
+void FSMC_NANDCmd(u32 FSMC_Bank, FunctionalState NewState);
+void FSMC_PCCARDCmd(FunctionalState NewState);
+void FSMC_NANDECCCmd(u32 FSMC_Bank, FunctionalState NewState);
+u32 FSMC_GetECC(u32 FSMC_Bank);
+void FSMC_ITConfig(u32 FSMC_Bank, u32 FSMC_IT, FunctionalState NewState);
+FlagStatus FSMC_GetFlagStatus(u32 FSMC_Bank, u32 FSMC_FLAG);
+void FSMC_ClearFlag(u32 FSMC_Bank, u32 FSMC_FLAG);
+ITStatus FSMC_GetITStatus(u32 FSMC_Bank, u32 FSMC_IT);
+void FSMC_ClearITPendingBit(u32 FSMC_Bank, u32 FSMC_IT);
+
+#endif /*__STM32F10x_FSMC_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_gpio.h b/src/stm32lib/inc/stm32f10x_gpio.h new file mode 100644 index 0000000..ae7f0c2 --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_gpio.h @@ -0,0 +1,243 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_gpio.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* GPIO firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_GPIO_H
+#define __STM32F10x_GPIO_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+#define IS_GPIO_ALL_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == GPIOA_BASE) || \
+ ((*(u32*)&(PERIPH)) == GPIOB_BASE) || \
+ ((*(u32*)&(PERIPH)) == GPIOC_BASE) || \
+ ((*(u32*)&(PERIPH)) == GPIOD_BASE) || \
+ ((*(u32*)&(PERIPH)) == GPIOE_BASE) || \
+ ((*(u32*)&(PERIPH)) == GPIOF_BASE) || \
+ ((*(u32*)&(PERIPH)) == GPIOG_BASE))
+
+/* Output Maximum frequency selection ----------------------------------------*/
+typedef enum
+{
+ GPIO_Speed_10MHz = 1,
+ GPIO_Speed_2MHz,
+ GPIO_Speed_50MHz
+}GPIOSpeed_TypeDef;
+
+#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_Speed_10MHz) || ((SPEED) == GPIO_Speed_2MHz) || \
+ ((SPEED) == GPIO_Speed_50MHz))
+
+/* Configuration Mode enumeration --------------------------------------------*/
+typedef enum
+{ GPIO_Mode_AIN = 0x0,
+ GPIO_Mode_IN_FLOATING = 0x04,
+ GPIO_Mode_IPD = 0x28,
+ GPIO_Mode_IPU = 0x48,
+ GPIO_Mode_Out_OD = 0x14,
+ GPIO_Mode_Out_PP = 0x10,
+ GPIO_Mode_AF_OD = 0x1C,
+ GPIO_Mode_AF_PP = 0x18
+}GPIOMode_TypeDef;
+
+#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_Mode_AIN) || ((MODE) == GPIO_Mode_IN_FLOATING) || \
+ ((MODE) == GPIO_Mode_IPD) || ((MODE) == GPIO_Mode_IPU) || \
+ ((MODE) == GPIO_Mode_Out_OD) || ((MODE) == GPIO_Mode_Out_PP) || \
+ ((MODE) == GPIO_Mode_AF_OD) || ((MODE) == GPIO_Mode_AF_PP))
+
+/* GPIO Init structure definition */
+typedef struct
+{
+ u16 GPIO_Pin;
+ GPIOSpeed_TypeDef GPIO_Speed;
+ GPIOMode_TypeDef GPIO_Mode;
+}GPIO_InitTypeDef;
+
+/* Bit_SET and Bit_RESET enumeration -----------------------------------------*/
+typedef enum
+{ Bit_RESET = 0,
+ Bit_SET
+}BitAction;
+#define IS_GPIO_BIT_ACTION(ACTION) (((ACTION) == Bit_RESET) || ((ACTION) == Bit_SET))
+
+/* Exported constants --------------------------------------------------------*/
+/* GPIO pins define ----------------------------------------------------------*/
+#define GPIO_Pin_0 ((u16)0x0001) /* Pin 0 selected */
+#define GPIO_Pin_1 ((u16)0x0002) /* Pin 1 selected */
+#define GPIO_Pin_2 ((u16)0x0004) /* Pin 2 selected */
+#define GPIO_Pin_3 ((u16)0x0008) /* Pin 3 selected */
+#define GPIO_Pin_4 ((u16)0x0010) /* Pin 4 selected */
+#define GPIO_Pin_5 ((u16)0x0020) /* Pin 5 selected */
+#define GPIO_Pin_6 ((u16)0x0040) /* Pin 6 selected */
+#define GPIO_Pin_7 ((u16)0x0080) /* Pin 7 selected */
+#define GPIO_Pin_8 ((u16)0x0100) /* Pin 8 selected */
+#define GPIO_Pin_9 ((u16)0x0200) /* Pin 9 selected */
+#define GPIO_Pin_10 ((u16)0x0400) /* Pin 10 selected */
+#define GPIO_Pin_11 ((u16)0x0800) /* Pin 11 selected */
+#define GPIO_Pin_12 ((u16)0x1000) /* Pin 12 selected */
+#define GPIO_Pin_13 ((u16)0x2000) /* Pin 13 selected */
+#define GPIO_Pin_14 ((u16)0x4000) /* Pin 14 selected */
+#define GPIO_Pin_15 ((u16)0x8000) /* Pin 15 selected */
+#define GPIO_Pin_All ((u16)0xFFFF) /* All pins selected */
+
+#define IS_GPIO_PIN(PIN) ((((PIN) & (u16)0x00) == 0x00) && ((PIN) != (u16)0x00))
+
+#define IS_GET_GPIO_PIN(PIN) (((PIN) == GPIO_Pin_0) || \
+ ((PIN) == GPIO_Pin_1) || \
+ ((PIN) == GPIO_Pin_2) || \
+ ((PIN) == GPIO_Pin_3) || \
+ ((PIN) == GPIO_Pin_4) || \
+ ((PIN) == GPIO_Pin_5) || \
+ ((PIN) == GPIO_Pin_6) || \
+ ((PIN) == GPIO_Pin_7) || \
+ ((PIN) == GPIO_Pin_8) || \
+ ((PIN) == GPIO_Pin_9) || \
+ ((PIN) == GPIO_Pin_10) || \
+ ((PIN) == GPIO_Pin_11) || \
+ ((PIN) == GPIO_Pin_12) || \
+ ((PIN) == GPIO_Pin_13) || \
+ ((PIN) == GPIO_Pin_14) || \
+ ((PIN) == GPIO_Pin_15))
+
+/* GPIO Remap define ---------------------------------------------------------*/
+#define GPIO_Remap_SPI1 ((u32)0x00000001) /* SPI1 Alternate Function mapping */
+#define GPIO_Remap_I2C1 ((u32)0x00000002) /* I2C1 Alternate Function mapping */
+#define GPIO_Remap_USART1 ((u32)0x00000004) /* USART1 Alternate Function mapping */
+#define GPIO_Remap_USART2 ((u32)0x00000008) /* USART2 Alternate Function mapping */
+#define GPIO_PartialRemap_USART3 ((u32)0x00140010) /* USART3 Partial Alternate Function mapping */
+#define GPIO_FullRemap_USART3 ((u32)0x00140030) /* USART3 Full Alternate Function mapping */
+#define GPIO_PartialRemap_TIM1 ((u32)0x00160040) /* TIM1 Partial Alternate Function mapping */
+#define GPIO_FullRemap_TIM1 ((u32)0x001600C0) /* TIM1 Full Alternate Function mapping */
+#define GPIO_PartialRemap1_TIM2 ((u32)0x00180100) /* TIM2 Partial1 Alternate Function mapping */
+#define GPIO_PartialRemap2_TIM2 ((u32)0x00180200) /* TIM2 Partial2 Alternate Function mapping */
+#define GPIO_FullRemap_TIM2 ((u32)0x00180300) /* TIM2 Full Alternate Function mapping */
+#define GPIO_PartialRemap_TIM3 ((u32)0x001A0800) /* TIM3 Partial Alternate Function mapping */
+#define GPIO_FullRemap_TIM3 ((u32)0x001A0C00) /* TIM3 Full Alternate Function mapping */
+#define GPIO_Remap_TIM4 ((u32)0x00001000) /* TIM4 Alternate Function mapping */
+#define GPIO_Remap1_CAN ((u32)0x001D4000) /* CAN Alternate Function mapping */
+#define GPIO_Remap2_CAN ((u32)0x001D6000) /* CAN Alternate Function mapping */
+#define GPIO_Remap_PD01 ((u32)0x00008000) /* PD01 Alternate Function mapping */
+#define GPIO_Remap_TIM5CH4_LSI ((u32)0x00200001) /* LSI connected to TIM5 Channel4 input capture for calibration */
+#define GPIO_Remap_ADC1_ETRGINJ ((u32)0x00200002) /* ADC1 External Trigger Injected Conversion remapping */
+#define GPIO_Remap_ADC1_ETRGREG ((u32)0x00200004) /* ADC1 External Trigger Regular Conversion remapping */
+#define GPIO_Remap_ADC2_ETRGINJ ((u32)0x00200008) /* ADC2 External Trigger Injected Conversion remapping */
+#define GPIO_Remap_ADC2_ETRGREG ((u32)0x00200010) /* ADC2 External Trigger Regular Conversion remapping */
+#define GPIO_Remap_SWJ_NoJTRST ((u32)0x00300100) /* Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST */
+#define GPIO_Remap_SWJ_JTAGDisable ((u32)0x00300200) /* JTAG-DP Disabled and SW-DP Enabled */
+#define GPIO_Remap_SWJ_Disable ((u32)0x00300400) /* Full SWJ Disabled (JTAG-DP + SW-DP) */
+
+
+#define IS_GPIO_REMAP(REMAP) (((REMAP) == GPIO_Remap_SPI1) || ((REMAP) == GPIO_Remap_I2C1) || \
+ ((REMAP) == GPIO_Remap_USART1) || ((REMAP) == GPIO_Remap_USART2) || \
+ ((REMAP) == GPIO_PartialRemap_USART3) || ((REMAP) == GPIO_FullRemap_USART3) || \
+ ((REMAP) == GPIO_PartialRemap_TIM1) || ((REMAP) == GPIO_FullRemap_TIM1) || \
+ ((REMAP) == GPIO_PartialRemap1_TIM2) || ((REMAP) == GPIO_PartialRemap2_TIM2) || \
+ ((REMAP) == GPIO_FullRemap_TIM2) || ((REMAP) == GPIO_PartialRemap_TIM3) || \
+ ((REMAP) == GPIO_FullRemap_TIM3) || ((REMAP) == GPIO_Remap_TIM4) || \
+ ((REMAP) == GPIO_Remap1_CAN) || ((REMAP) == GPIO_Remap2_CAN) || \
+ ((REMAP) == GPIO_Remap_PD01) || ((REMAP) == GPIO_Remap_TIM5CH4_LSI) || \
+ ((REMAP) == GPIO_Remap_ADC1_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC1_ETRGREG) || \
+ ((REMAP) == GPIO_Remap_ADC2_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC2_ETRGREG) || \
+ ((REMAP) == GPIO_Remap_SWJ_NoJTRST) || ((REMAP) == GPIO_Remap_SWJ_JTAGDisable)|| \
+ ((REMAP) == GPIO_Remap_SWJ_Disable))
+
+/* GPIO Port Sources ---------------------------------------------------------*/
+#define GPIO_PortSourceGPIOA ((u8)0x00)
+#define GPIO_PortSourceGPIOB ((u8)0x01)
+#define GPIO_PortSourceGPIOC ((u8)0x02)
+#define GPIO_PortSourceGPIOD ((u8)0x03)
+#define GPIO_PortSourceGPIOE ((u8)0x04)
+#define GPIO_PortSourceGPIOF ((u8)0x05)
+#define GPIO_PortSourceGPIOG ((u8)0x06)
+
+#define IS_GPIO_EVENTOUT_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOB) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOC) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOD) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOE))
+
+#define IS_GPIO_EXTI_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOB) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOC) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOD) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOE) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOF) || \
+ ((PORTSOURCE) == GPIO_PortSourceGPIOG))
+
+/* GPIO Pin sources ----------------------------------------------------------*/
+#define GPIO_PinSource0 ((u8)0x00)
+#define GPIO_PinSource1 ((u8)0x01)
+#define GPIO_PinSource2 ((u8)0x02)
+#define GPIO_PinSource3 ((u8)0x03)
+#define GPIO_PinSource4 ((u8)0x04)
+#define GPIO_PinSource5 ((u8)0x05)
+#define GPIO_PinSource6 ((u8)0x06)
+#define GPIO_PinSource7 ((u8)0x07)
+#define GPIO_PinSource8 ((u8)0x08)
+#define GPIO_PinSource9 ((u8)0x09)
+#define GPIO_PinSource10 ((u8)0x0A)
+#define GPIO_PinSource11 ((u8)0x0B)
+#define GPIO_PinSource12 ((u8)0x0C)
+#define GPIO_PinSource13 ((u8)0x0D)
+#define GPIO_PinSource14 ((u8)0x0E)
+#define GPIO_PinSource15 ((u8)0x0F)
+
+#define IS_GPIO_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == GPIO_PinSource0) || \
+ ((PINSOURCE) == GPIO_PinSource1) || \
+ ((PINSOURCE) == GPIO_PinSource2) || \
+ ((PINSOURCE) == GPIO_PinSource3) || \
+ ((PINSOURCE) == GPIO_PinSource4) || \
+ ((PINSOURCE) == GPIO_PinSource5) || \
+ ((PINSOURCE) == GPIO_PinSource6) || \
+ ((PINSOURCE) == GPIO_PinSource7) || \
+ ((PINSOURCE) == GPIO_PinSource8) || \
+ ((PINSOURCE) == GPIO_PinSource9) || \
+ ((PINSOURCE) == GPIO_PinSource10) || \
+ ((PINSOURCE) == GPIO_PinSource11) || \
+ ((PINSOURCE) == GPIO_PinSource12) || \
+ ((PINSOURCE) == GPIO_PinSource13) || \
+ ((PINSOURCE) == GPIO_PinSource14) || \
+ ((PINSOURCE) == GPIO_PinSource15))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+#ifdef __cplusplus
+extern "C" {
+#endif
+void GPIO_DeInit(GPIO_TypeDef* GPIOx);
+void GPIO_AFIODeInit(void);
+void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct);
+void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct);
+u8 GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin);
+u16 GPIO_ReadInputData(GPIO_TypeDef* GPIOx);
+u8 GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin);
+u16 GPIO_ReadOutputData(GPIO_TypeDef* GPIOx);
+void GPIO_SetBits(GPIO_TypeDef* GPIOx, u16 GPIO_Pin);
+void GPIO_ResetBits(GPIO_TypeDef* GPIOx, u16 GPIO_Pin);
+void GPIO_WriteBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin, BitAction BitVal);
+void GPIO_Write(GPIO_TypeDef* GPIOx, u16 PortVal);
+void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, u16 GPIO_Pin);
+void GPIO_EventOutputConfig(u8 GPIO_PortSource, u8 GPIO_PinSource);
+void GPIO_EventOutputCmd(FunctionalState NewState);
+void GPIO_PinRemapConfig(u32 GPIO_Remap, FunctionalState NewState);
+void GPIO_EXTILineConfig(u8 GPIO_PortSource, u8 GPIO_PinSource);
+
+#ifdef __cplusplus
+}
+#endif
+#endif /* __STM32F10x_GPIO_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_i2c.h b/src/stm32lib/inc/stm32f10x_i2c.h new file mode 100644 index 0000000..7dd6d7d --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_i2c.h @@ -0,0 +1,281 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_i2c.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* I2C firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_I2C_H
+#define __STM32F10x_I2C_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* I2C Init structure definition */
+typedef struct
+{
+ u16 I2C_Mode;
+ u16 I2C_DutyCycle;
+ u16 I2C_OwnAddress1;
+ u16 I2C_Ack;
+ u16 I2C_AcknowledgedAddress;
+ u32 I2C_ClockSpeed;
+}I2C_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+#define IS_I2C_ALL_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == I2C1_BASE) || \
+ ((*(u32*)&(PERIPH)) == I2C2_BASE))
+
+/* I2C modes */
+#define I2C_Mode_I2C ((u16)0x0000)
+#define I2C_Mode_SMBusDevice ((u16)0x0002)
+#define I2C_Mode_SMBusHost ((u16)0x000A)
+
+#define IS_I2C_MODE(MODE) (((MODE) == I2C_Mode_I2C) || \
+ ((MODE) == I2C_Mode_SMBusDevice) || \
+ ((MODE) == I2C_Mode_SMBusHost))
+/* I2C duty cycle in fast mode */
+#define I2C_DutyCycle_16_9 ((u16)0x4000)
+#define I2C_DutyCycle_2 ((u16)0xBFFF)
+
+#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DutyCycle_16_9) || \
+ ((CYCLE) == I2C_DutyCycle_2))
+
+/* I2C cknowledgementy */
+#define I2C_Ack_Enable ((u16)0x0400)
+#define I2C_Ack_Disable ((u16)0x0000)
+
+#define IS_I2C_ACK_STATE(STATE) (((STATE) == I2C_Ack_Enable) || \
+ ((STATE) == I2C_Ack_Disable))
+
+/* I2C transfer direction */
+#define I2C_Direction_Transmitter ((u8)0x00)
+#define I2C_Direction_Receiver ((u8)0x01)
+
+#define IS_I2C_DIRECTION(DIRECTION) (((DIRECTION) == I2C_Direction_Transmitter) || \
+ ((DIRECTION) == I2C_Direction_Receiver))
+
+/* I2C acknowledged address defines */
+#define I2C_AcknowledgedAddress_7bit ((u16)0x4000)
+#define I2C_AcknowledgedAddress_10bit ((u16)0xC000)
+
+#define IS_I2C_ACKNOWLEDGE_ADDRESS(ADDRESS) (((ADDRESS) == I2C_AcknowledgedAddress_7bit) || \
+ ((ADDRESS) == I2C_AcknowledgedAddress_10bit))
+
+/* I2C registers */
+#define I2C_Register_CR1 ((u8)0x00)
+#define I2C_Register_CR2 ((u8)0x04)
+#define I2C_Register_OAR1 ((u8)0x08)
+#define I2C_Register_OAR2 ((u8)0x0C)
+#define I2C_Register_DR ((u8)0x10)
+#define I2C_Register_SR1 ((u8)0x14)
+#define I2C_Register_SR2 ((u8)0x18)
+#define I2C_Register_CCR ((u8)0x1C)
+#define I2C_Register_TRISE ((u8)0x20)
+
+#define IS_I2C_REGISTER(REGISTER) (((REGISTER) == I2C_Register_CR1) || \
+ ((REGISTER) == I2C_Register_CR2) || \
+ ((REGISTER) == I2C_Register_OAR1) || \
+ ((REGISTER) == I2C_Register_OAR2) || \
+ ((REGISTER) == I2C_Register_DR) || \
+ ((REGISTER) == I2C_Register_SR1) || \
+ ((REGISTER) == I2C_Register_SR2) || \
+ ((REGISTER) == I2C_Register_CCR) || \
+ ((REGISTER) == I2C_Register_TRISE))
+
+/* I2C SMBus alert pin level */
+#define I2C_SMBusAlert_Low ((u16)0x2000)
+#define I2C_SMBusAlert_High ((u16)0xDFFF)
+
+#define IS_I2C_SMBUS_ALERT(ALERT) (((ALERT) == I2C_SMBusAlert_Low) || \
+ ((ALERT) == I2C_SMBusAlert_High))
+
+/* I2C PEC position */
+#define I2C_PECPosition_Next ((u16)0x0800)
+#define I2C_PECPosition_Current ((u16)0xF7FF)
+
+#define IS_I2C_PEC_POSITION(POSITION) (((POSITION) == I2C_PECPosition_Next) || \
+ ((POSITION) == I2C_PECPosition_Current))
+
+/* I2C interrupts definition */
+#define I2C_IT_BUF ((u16)0x0400)
+#define I2C_IT_EVT ((u16)0x0200)
+#define I2C_IT_ERR ((u16)0x0100)
+
+#define IS_I2C_CONFIG_IT(IT) ((((IT) & (u16)0xF8FF) == 0x00) && ((IT) != 0x00))
+
+/* I2C interrupts definition */
+#define I2C_IT_SMBALERT ((u32)0x01008000)
+#define I2C_IT_TIMEOUT ((u32)0x01004000)
+#define I2C_IT_PECERR ((u32)0x01001000)
+#define I2C_IT_OVR ((u32)0x01000800)
+#define I2C_IT_AF ((u32)0x01000400)
+#define I2C_IT_ARLO ((u32)0x01000200)
+#define I2C_IT_BERR ((u32)0x01000100)
+#define I2C_IT_TXE ((u32)0x06000080)
+#define I2C_IT_RXNE ((u32)0x06000040)
+#define I2C_IT_STOPF ((u32)0x02000010)
+#define I2C_IT_ADD10 ((u32)0x02000008)
+#define I2C_IT_BTF ((u32)0x02000004)
+#define I2C_IT_ADDR ((u32)0x02000002)
+#define I2C_IT_SB ((u32)0x02000001)
+
+#define IS_I2C_CLEAR_IT(IT) ((((IT) & (u16)0x20FF) == 0x00) && ((IT) != (u16)0x00))
+
+#define IS_I2C_GET_IT(IT) (((IT) == I2C_IT_SMBALERT) || ((IT) == I2C_IT_TIMEOUT) || \
+ ((IT) == I2C_IT_PECERR) || ((IT) == I2C_IT_OVR) || \
+ ((IT) == I2C_IT_AF) || ((IT) == I2C_IT_ARLO) || \
+ ((IT) == I2C_IT_BERR) || ((IT) == I2C_IT_TXE) || \
+ ((IT) == I2C_IT_RXNE) || ((IT) == I2C_IT_STOPF) || \
+ ((IT) == I2C_IT_ADD10) || ((IT) == I2C_IT_BTF) || \
+ ((IT) == I2C_IT_ADDR) || ((IT) == I2C_IT_SB))
+
+/* I2C flags definition */
+/* SR2 register flags */
+#define I2C_FLAG_DUALF ((u32)0x00800000)
+#define I2C_FLAG_SMBHOST ((u32)0x00400000)
+#define I2C_FLAG_SMBDEFAULT ((u32)0x00200000)
+#define I2C_FLAG_GENCALL ((u32)0x00100000)
+#define I2C_FLAG_TRA ((u32)0x00040000)
+#define I2C_FLAG_BUSY ((u32)0x00020000)
+#define I2C_FLAG_MSL ((u32)0x00010000)
+/* SR1 register flags */
+#define I2C_FLAG_SMBALERT ((u32)0x10008000)
+#define I2C_FLAG_TIMEOUT ((u32)0x10004000)
+#define I2C_FLAG_PECERR ((u32)0x10001000)
+#define I2C_FLAG_OVR ((u32)0x10000800)
+#define I2C_FLAG_AF ((u32)0x10000400)
+#define I2C_FLAG_ARLO ((u32)0x10000200)
+#define I2C_FLAG_BERR ((u32)0x10000100)
+#define I2C_FLAG_TXE ((u32)0x10000080)
+#define I2C_FLAG_RXNE ((u32)0x10000040)
+#define I2C_FLAG_STOPF ((u32)0x10000010)
+#define I2C_FLAG_ADD10 ((u32)0x10000008)
+#define I2C_FLAG_BTF ((u32)0x10000004)
+#define I2C_FLAG_ADDR ((u32)0x10000002)
+#define I2C_FLAG_SB ((u32)0x10000001)
+
+#define IS_I2C_CLEAR_FLAG(FLAG) ((((FLAG) & (u16)0x20FF) == 0x00) && ((FLAG) != (u16)0x00))
+
+#define IS_I2C_GET_FLAG(FLAG) (((FLAG) == I2C_FLAG_DUALF) || ((FLAG) == I2C_FLAG_SMBHOST) || \
+ ((FLAG) == I2C_FLAG_SMBDEFAULT) || ((FLAG) == I2C_FLAG_GENCALL) || \
+ ((FLAG) == I2C_FLAG_TRA) || ((FLAG) == I2C_FLAG_BUSY) || \
+ ((FLAG) == I2C_FLAG_MSL) || ((FLAG) == I2C_FLAG_SMBALERT) || \
+ ((FLAG) == I2C_FLAG_TIMEOUT) || ((FLAG) == I2C_FLAG_PECERR) || \
+ ((FLAG) == I2C_FLAG_OVR) || ((FLAG) == I2C_FLAG_AF) || \
+ ((FLAG) == I2C_FLAG_ARLO) || ((FLAG) == I2C_FLAG_BERR) || \
+ ((FLAG) == I2C_FLAG_TXE) || ((FLAG) == I2C_FLAG_RXNE) || \
+ ((FLAG) == I2C_FLAG_STOPF) || ((FLAG) == I2C_FLAG_ADD10) || \
+ ((FLAG) == I2C_FLAG_BTF) || ((FLAG) == I2C_FLAG_ADDR) || \
+ ((FLAG) == I2C_FLAG_SB))
+
+/* I2C Events */
+/* EV1 */
+#define I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED ((u32)0x00060082) /* TRA, BUSY, TXE and ADDR flags */
+#define I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED ((u32)0x00020002) /* BUSY and ADDR flags */
+#define I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED ((u32)0x00860080) /* DUALF, TRA, BUSY and TXE flags */
+#define I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED ((u32)0x00820000) /* DUALF and BUSY flags */
+#define I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED ((u32)0x00120000) /* GENCALL and BUSY flags */
+
+/* EV2 */
+#define I2C_EVENT_SLAVE_BYTE_RECEIVED ((u32)0x00020040) /* BUSY and RXNE flags */
+
+/* EV3 */
+#define I2C_EVENT_SLAVE_BYTE_TRANSMITTED ((u32)0x00060084) /* TRA, BUSY, TXE and BTF flags */
+
+/* EV4 */
+#define I2C_EVENT_SLAVE_STOP_DETECTED ((u32)0x00000010) /* STOPF flag */
+
+/* EV5 */
+#define I2C_EVENT_MASTER_MODE_SELECT ((u32)0x00030001) /* BUSY, MSL and SB flag */
+
+/* EV6 */
+#define I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED ((u32)0x00070082) /* BUSY, MSL, ADDR, TXE and TRA flags */
+#define I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED ((u32)0x00030002) /* BUSY, MSL and ADDR flags */
+
+/* EV7 */
+#define I2C_EVENT_MASTER_BYTE_RECEIVED ((u32)0x00030040) /* BUSY, MSL and RXNE flags */
+
+/* EV8 */
+#define I2C_EVENT_MASTER_BYTE_TRANSMITTED ((u32)0x00070084) /* TRA, BUSY, MSL, TXE and BTF flags */
+
+/* EV9 */
+#define I2C_EVENT_MASTER_MODE_ADDRESS10 ((u32)0x00030008) /* BUSY, MSL and ADD10 flags */
+
+/* EV3_2 */
+#define I2C_EVENT_SLAVE_ACK_FAILURE ((u32)0x00000400) /* AF flag */
+
+#define IS_I2C_EVENT(EVENT) (((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED) || \
+ ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED) || \
+ ((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED) || \
+ ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED) || \
+ ((EVENT) == I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED) || \
+ ((EVENT) == I2C_EVENT_SLAVE_BYTE_RECEIVED) || \
+ ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF)) || \
+ ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL)) || \
+ ((EVENT) == I2C_EVENT_SLAVE_BYTE_TRANSMITTED) || \
+ ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF)) || \
+ ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL)) || \
+ ((EVENT) == I2C_EVENT_SLAVE_STOP_DETECTED) || \
+ ((EVENT) == I2C_EVENT_MASTER_MODE_SELECT) || \
+ ((EVENT) == I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED) || \
+ ((EVENT) == I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED) || \
+ ((EVENT) == I2C_EVENT_MASTER_BYTE_RECEIVED) || \
+ ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTED) || \
+ ((EVENT) == I2C_EVENT_MASTER_MODE_ADDRESS10) || \
+ ((EVENT) == I2C_EVENT_SLAVE_ACK_FAILURE))
+
+/* I2C own address1 -----------------------------------------------------------*/
+#define IS_I2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x3FF)
+/* I2C clock speed ------------------------------------------------------------*/
+#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) >= 0x1) && ((SPEED) <= 400000))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void I2C_DeInit(I2C_TypeDef* I2Cx);
+void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct);
+void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct);
+void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, u8 Address);
+void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_ITConfig(I2C_TypeDef* I2Cx, u16 I2C_IT, FunctionalState NewState);
+void I2C_SendData(I2C_TypeDef* I2Cx, u8 Data);
+u8 I2C_ReceiveData(I2C_TypeDef* I2Cx);
+void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, u8 Address, u8 I2C_Direction);
+u16 I2C_ReadRegister(I2C_TypeDef* I2Cx, u8 I2C_Register);
+void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, u16 I2C_SMBusAlert);
+void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, u16 I2C_PECPosition);
+void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState);
+u8 I2C_GetPEC(I2C_TypeDef* I2Cx);
+void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, u16 I2C_DutyCycle);
+u32 I2C_GetLastEvent(I2C_TypeDef* I2Cx);
+ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, u32 I2C_EVENT);
+FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, u32 I2C_FLAG);
+void I2C_ClearFlag(I2C_TypeDef* I2Cx, u32 I2C_FLAG);
+ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, u32 I2C_IT);
+void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, u32 I2C_IT);
+
+#endif /*__STM32F10x_I2C_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_iwdg.h b/src/stm32lib/inc/stm32f10x_iwdg.h new file mode 100644 index 0000000..287950f --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_iwdg.h @@ -0,0 +1,69 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_iwdg.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* IWDG firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IWDG_H
+#define __STM32F10x_IWDG_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Write access to IWDG_PR and IWDG_RLR registers */
+#define IWDG_WriteAccess_Enable ((u16)0x5555)
+#define IWDG_WriteAccess_Disable ((u16)0x0000)
+
+#define IS_IWDG_WRITE_ACCESS(ACCESS) (((ACCESS) == IWDG_WriteAccess_Enable) || \
+ ((ACCESS) == IWDG_WriteAccess_Disable))
+
+/* IWDG prescaler */
+#define IWDG_Prescaler_4 ((u8)0x00)
+#define IWDG_Prescaler_8 ((u8)0x01)
+#define IWDG_Prescaler_16 ((u8)0x02)
+#define IWDG_Prescaler_32 ((u8)0x03)
+#define IWDG_Prescaler_64 ((u8)0x04)
+#define IWDG_Prescaler_128 ((u8)0x05)
+#define IWDG_Prescaler_256 ((u8)0x06)
+
+#define IS_IWDG_PRESCALER(PRESCALER) (((PRESCALER) == IWDG_Prescaler_4) || \
+ ((PRESCALER) == IWDG_Prescaler_8) || \
+ ((PRESCALER) == IWDG_Prescaler_16) || \
+ ((PRESCALER) == IWDG_Prescaler_32) || \
+ ((PRESCALER) == IWDG_Prescaler_64) || \
+ ((PRESCALER) == IWDG_Prescaler_128)|| \
+ ((PRESCALER) == IWDG_Prescaler_256))
+
+/* IWDG Flag */
+#define IWDG_FLAG_PVU ((u16)0x0001)
+#define IWDG_FLAG_RVU ((u16)0x0002)
+
+#define IS_IWDG_FLAG(FLAG) (((FLAG) == IWDG_FLAG_PVU) || ((FLAG) == IWDG_FLAG_RVU))
+
+#define IS_IWDG_RELOAD(RELOAD) ((RELOAD) <= 0xFFF)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void IWDG_WriteAccessCmd(u16 IWDG_WriteAccess);
+void IWDG_SetPrescaler(u8 IWDG_Prescaler);
+void IWDG_SetReload(u16 Reload);
+void IWDG_ReloadCounter(void);
+void IWDG_Enable(void);
+FlagStatus IWDG_GetFlagStatus(u16 IWDG_FLAG);
+
+#endif /* __STM32F10x_IWDG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_lib.h b/src/stm32lib/inc/stm32f10x_lib.h new file mode 100644 index 0000000..beff887 --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_lib.h @@ -0,0 +1,124 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_lib.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file includes the peripherals header files in the
+* user application.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_LIB_H
+#define __STM32F10x_LIB_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+#ifdef _ADC
+ #include "stm32f10x_adc.h"
+#endif /*_ADC */
+
+#ifdef _BKP
+ #include "stm32f10x_bkp.h"
+#endif /*_BKP */
+
+#ifdef _CAN
+ #include "stm32f10x_can.h"
+#endif /*_CAN */
+
+#ifdef _CRC
+ #include "stm32f10x_crc.h"
+#endif /*_CRC */
+
+#ifdef _DAC
+ #include "stm32f10x_dac.h"
+#endif /*_DAC */
+
+#ifdef _DBGMCU
+ #include "stm32f10x_dbgmcu.h"
+#endif /*_DBGMCU */
+
+#ifdef _DMA
+ #include "stm32f10x_dma.h"
+#endif /*_DMA */
+
+#ifdef _EXTI
+ #include "stm32f10x_exti.h"
+#endif /*_EXTI */
+
+#ifdef _FLASH
+ #include "stm32f10x_flash.h"
+#endif /*_FLASH */
+
+#ifdef _FSMC
+ #include "stm32f10x_fsmc.h"
+#endif /*_FSMC */
+
+#ifdef _GPIO
+ #include "stm32f10x_gpio.h"
+#endif /*_GPIO */
+
+#ifdef _I2C
+ #include "stm32f10x_i2c.h"
+#endif /*_I2C */
+
+#ifdef _IWDG
+ #include "stm32f10x_iwdg.h"
+#endif /*_IWDG */
+
+#ifdef _NVIC
+ #include "stm32f10x_nvic.h"
+#endif /*_NVIC */
+
+#ifdef _PWR
+ #include "stm32f10x_pwr.h"
+#endif /*_PWR */
+
+#ifdef _RCC
+ #include "stm32f10x_rcc.h"
+#endif /*_RCC */
+
+#ifdef _RTC
+ #include "stm32f10x_rtc.h"
+#endif /*_RTC */
+
+#ifdef _SDIO
+ #include "stm32f10x_sdio.h"
+#endif /*_SDIO */
+
+#ifdef _SPI
+ #include "stm32f10x_spi.h"
+#endif /*_SPI */
+
+#ifdef _SysTick
+ #include "stm32f10x_systick.h"
+#endif /*_SysTick */
+
+#ifdef _TIM
+ #include "stm32f10x_tim.h"
+#endif /*_TIM */
+
+#ifdef _USART
+ #include "stm32f10x_usart.h"
+#endif /*_USART */
+
+#ifdef _WWDG
+ #include "stm32f10x_wwdg.h"
+#endif /*_WWDG */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void debug(void);
+
+#endif /* __STM32F10x_LIB_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_map.h b/src/stm32lib/inc/stm32f10x_map.h new file mode 100644 index 0000000..33829fc --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_map.h @@ -0,0 +1,1187 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_map.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the peripheral register's definitions
+* and memory mapping.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_MAP_H
+#define __STM32F10x_MAP_H
+
+#ifndef EXT
+ #define EXT extern
+#endif /* EXT */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_conf.h"
+#include "stm32f10x_type.h"
+#include "cortexm3_macro.h"
+
+/* Exported types ------------------------------------------------------------*/
+/******************************************************************************/
+/* Peripheral registers structures */
+/******************************************************************************/
+
+/*------------------------ Analog to Digital Converter -----------------------*/
+typedef struct
+{
+ vu32 SR;
+ vu32 CR1;
+ vu32 CR2;
+ vu32 SMPR1;
+ vu32 SMPR2;
+ vu32 JOFR1;
+ vu32 JOFR2;
+ vu32 JOFR3;
+ vu32 JOFR4;
+ vu32 HTR;
+ vu32 LTR;
+ vu32 SQR1;
+ vu32 SQR2;
+ vu32 SQR3;
+ vu32 JSQR;
+ vu32 JDR1;
+ vu32 JDR2;
+ vu32 JDR3;
+ vu32 JDR4;
+ vu32 DR;
+} ADC_TypeDef;
+
+/*------------------------ Backup Registers ----------------------------------*/
+typedef struct
+{
+ u32 RESERVED0;
+ vu16 DR1;
+ u16 RESERVED1;
+ vu16 DR2;
+ u16 RESERVED2;
+ vu16 DR3;
+ u16 RESERVED3;
+ vu16 DR4;
+ u16 RESERVED4;
+ vu16 DR5;
+ u16 RESERVED5;
+ vu16 DR6;
+ u16 RESERVED6;
+ vu16 DR7;
+ u16 RESERVED7;
+ vu16 DR8;
+ u16 RESERVED8;
+ vu16 DR9;
+ u16 RESERVED9;
+ vu16 DR10;
+ u16 RESERVED10;
+ vu16 RTCCR;
+ u16 RESERVED11;
+ vu16 CR;
+ u16 RESERVED12;
+ vu16 CSR;
+ u16 RESERVED13[5];
+ vu16 DR11;
+ u16 RESERVED14;
+ vu16 DR12;
+ u16 RESERVED15;
+ vu16 DR13;
+ u16 RESERVED16;
+ vu16 DR14;
+ u16 RESERVED17;
+ vu16 DR15;
+ u16 RESERVED18;
+ vu16 DR16;
+ u16 RESERVED19;
+ vu16 DR17;
+ u16 RESERVED20;
+ vu16 DR18;
+ u16 RESERVED21;
+ vu16 DR19;
+ u16 RESERVED22;
+ vu16 DR20;
+ u16 RESERVED23;
+ vu16 DR21;
+ u16 RESERVED24;
+ vu16 DR22;
+ u16 RESERVED25;
+ vu16 DR23;
+ u16 RESERVED26;
+ vu16 DR24;
+ u16 RESERVED27;
+ vu16 DR25;
+ u16 RESERVED28;
+ vu16 DR26;
+ u16 RESERVED29;
+ vu16 DR27;
+ u16 RESERVED30;
+ vu16 DR28;
+ u16 RESERVED31;
+ vu16 DR29;
+ u16 RESERVED32;
+ vu16 DR30;
+ u16 RESERVED33;
+ vu16 DR31;
+ u16 RESERVED34;
+ vu16 DR32;
+ u16 RESERVED35;
+ vu16 DR33;
+ u16 RESERVED36;
+ vu16 DR34;
+ u16 RESERVED37;
+ vu16 DR35;
+ u16 RESERVED38;
+ vu16 DR36;
+ u16 RESERVED39;
+ vu16 DR37;
+ u16 RESERVED40;
+ vu16 DR38;
+ u16 RESERVED41;
+ vu16 DR39;
+ u16 RESERVED42;
+ vu16 DR40;
+ u16 RESERVED43;
+ vu16 DR41;
+ u16 RESERVED44;
+ vu16 DR42;
+ u16 RESERVED45;
+} BKP_TypeDef;
+
+/*------------------------ Controller Area Network ---------------------------*/
+typedef struct
+{
+ vu32 TIR;
+ vu32 TDTR;
+ vu32 TDLR;
+ vu32 TDHR;
+} CAN_TxMailBox_TypeDef;
+
+typedef struct
+{
+ vu32 RIR;
+ vu32 RDTR;
+ vu32 RDLR;
+ vu32 RDHR;
+} CAN_FIFOMailBox_TypeDef;
+
+typedef struct
+{
+ vu32 FR1;
+ vu32 FR2;
+} CAN_FilterRegister_TypeDef;
+
+typedef struct
+{
+ vu32 MCR;
+ vu32 MSR;
+ vu32 TSR;
+ vu32 RF0R;
+ vu32 RF1R;
+ vu32 IER;
+ vu32 ESR;
+ vu32 BTR;
+ u32 RESERVED0[88];
+ CAN_TxMailBox_TypeDef sTxMailBox[3];
+ CAN_FIFOMailBox_TypeDef sFIFOMailBox[2];
+ u32 RESERVED1[12];
+ vu32 FMR;
+ vu32 FM1R;
+ u32 RESERVED2;
+ vu32 FS1R;
+ u32 RESERVED3;
+ vu32 FFA1R;
+ u32 RESERVED4;
+ vu32 FA1R;
+ u32 RESERVED5[8];
+ CAN_FilterRegister_TypeDef sFilterRegister[14];
+} CAN_TypeDef;
+
+/*------------------------ CRC calculation unit ------------------------------*/
+typedef struct
+{
+ vu32 DR;
+ vu8 IDR;
+ u8 RESERVED0;
+ u16 RESERVED1;
+ vu32 CR;
+} CRC_TypeDef;
+
+
+/*------------------------ Digital to Analog Converter -----------------------*/
+typedef struct
+{
+ vu32 CR;
+ vu32 SWTRIGR;
+ vu32 DHR12R1;
+ vu32 DHR12L1;
+ vu32 DHR8R1;
+ vu32 DHR12R2;
+ vu32 DHR12L2;
+ vu32 DHR8R2;
+ vu32 DHR12RD;
+ vu32 DHR12LD;
+ vu32 DHR8RD;
+ vu32 DOR1;
+ vu32 DOR2;
+} DAC_TypeDef;
+
+/*------------------------ Debug MCU -----------------------------------------*/
+typedef struct
+{
+ vu32 IDCODE;
+ vu32 CR;
+}DBGMCU_TypeDef;
+
+/*------------------------ DMA Controller ------------------------------------*/
+typedef struct
+{
+ vu32 CCR;
+ vu32 CNDTR;
+ vu32 CPAR;
+ vu32 CMAR;
+} DMA_Channel_TypeDef;
+
+typedef struct
+{
+ vu32 ISR;
+ vu32 IFCR;
+} DMA_TypeDef;
+
+/*------------------------ External Interrupt/Event Controller ---------------*/
+typedef struct
+{
+ vu32 IMR;
+ vu32 EMR;
+ vu32 RTSR;
+ vu32 FTSR;
+ vu32 SWIER;
+ vu32 PR;
+} EXTI_TypeDef;
+
+/*------------------------ FLASH and Option Bytes Registers ------------------*/
+typedef struct
+{
+ vu32 ACR;
+ vu32 KEYR;
+ vu32 OPTKEYR;
+ vu32 SR;
+ vu32 CR;
+ vu32 AR;
+ vu32 RESERVED;
+ vu32 OBR;
+ vu32 WRPR;
+} FLASH_TypeDef;
+
+typedef struct
+{
+ vu16 RDP;
+ vu16 USER;
+ vu16 Data0;
+ vu16 Data1;
+ vu16 WRP0;
+ vu16 WRP1;
+ vu16 WRP2;
+ vu16 WRP3;
+} OB_TypeDef;
+
+/*------------------------ Flexible Static Memory Controller -----------------*/
+typedef struct
+{
+ vu32 BTCR[8];
+} FSMC_Bank1_TypeDef;
+
+typedef struct
+{
+ vu32 BWTR[7];
+} FSMC_Bank1E_TypeDef;
+
+typedef struct
+{
+ vu32 PCR2;
+ vu32 SR2;
+ vu32 PMEM2;
+ vu32 PATT2;
+ u32 RESERVED0;
+ vu32 ECCR2;
+} FSMC_Bank2_TypeDef;
+
+typedef struct
+{
+ vu32 PCR3;
+ vu32 SR3;
+ vu32 PMEM3;
+ vu32 PATT3;
+ u32 RESERVED0;
+ vu32 ECCR3;
+} FSMC_Bank3_TypeDef;
+
+typedef struct
+{
+ vu32 PCR4;
+ vu32 SR4;
+ vu32 PMEM4;
+ vu32 PATT4;
+ vu32 PIO4;
+} FSMC_Bank4_TypeDef;
+
+/*------------------------ General Purpose and Alternate Function IO ---------*/
+typedef struct
+{
+ vu32 CRL;
+ vu32 CRH;
+ vu32 IDR;
+ vu32 ODR;
+ vu32 BSRR;
+ vu32 BRR;
+ vu32 LCKR;
+} GPIO_TypeDef;
+
+typedef struct
+{
+ vu32 EVCR;
+ vu32 MAPR;
+ vu32 EXTICR[4];
+} AFIO_TypeDef;
+
+/*------------------------ Inter-integrated Circuit Interface ----------------*/
+typedef struct
+{
+ vu16 CR1;
+ u16 RESERVED0;
+ vu16 CR2;
+ u16 RESERVED1;
+ vu16 OAR1;
+ u16 RESERVED2;
+ vu16 OAR2;
+ u16 RESERVED3;
+ vu16 DR;
+ u16 RESERVED4;
+ vu16 SR1;
+ u16 RESERVED5;
+ vu16 SR2;
+ u16 RESERVED6;
+ vu16 CCR;
+ u16 RESERVED7;
+ vu16 TRISE;
+ u16 RESERVED8;
+} I2C_TypeDef;
+
+/*------------------------ Independent WATCHDOG ------------------------------*/
+typedef struct
+{
+ vu32 KR;
+ vu32 PR;
+ vu32 RLR;
+ vu32 SR;
+} IWDG_TypeDef;
+
+/*------------------------ Nested Vectored Interrupt Controller --------------*/
+typedef struct
+{
+ vu32 ISER[2];
+ u32 RESERVED0[30];
+ vu32 ICER[2];
+ u32 RSERVED1[30];
+ vu32 ISPR[2];
+ u32 RESERVED2[30];
+ vu32 ICPR[2];
+ u32 RESERVED3[30];
+ vu32 IABR[2];
+ u32 RESERVED4[62];
+ vu32 IPR[15];
+} NVIC_TypeDef;
+
+typedef struct
+{
+ vuc32 CPUID;
+ vu32 ICSR;
+ vu32 VTOR;
+ vu32 AIRCR;
+ vu32 SCR;
+ vu32 CCR;
+ vu32 SHPR[3];
+ vu32 SHCSR;
+ vu32 CFSR;
+ vu32 HFSR;
+ vu32 DFSR;
+ vu32 MMFAR;
+ vu32 BFAR;
+ vu32 AFSR;
+} SCB_TypeDef;
+
+/*------------------------ Power Control -------------------------------------*/
+typedef struct
+{
+ vu32 CR;
+ vu32 CSR;
+} PWR_TypeDef;
+
+/*------------------------ Reset and Clock Control ---------------------------*/
+typedef struct
+{
+ vu32 CR;
+ vu32 CFGR;
+ vu32 CIR;
+ vu32 APB2RSTR;
+ vu32 APB1RSTR;
+ vu32 AHBENR;
+ vu32 APB2ENR;
+ vu32 APB1ENR;
+ vu32 BDCR;
+ vu32 CSR;
+} RCC_TypeDef;
+
+/*------------------------ Real-Time Clock -----------------------------------*/
+typedef struct
+{
+ vu16 CRH;
+ u16 RESERVED0;
+ vu16 CRL;
+ u16 RESERVED1;
+ vu16 PRLH;
+ u16 RESERVED2;
+ vu16 PRLL;
+ u16 RESERVED3;
+ vu16 DIVH;
+ u16 RESERVED4;
+ vu16 DIVL;
+ u16 RESERVED5;
+ vu16 CNTH;
+ u16 RESERVED6;
+ vu16 CNTL;
+ u16 RESERVED7;
+ vu16 ALRH;
+ u16 RESERVED8;
+ vu16 ALRL;
+ u16 RESERVED9;
+} RTC_TypeDef;
+
+/*------------------------ SD host Interface ---------------------------------*/
+typedef struct
+{
+ vu32 POWER;
+ vu32 CLKCR;
+ vu32 ARG;
+ vu32 CMD;
+ vuc32 RESPCMD;
+ vuc32 RESP1;
+ vuc32 RESP2;
+ vuc32 RESP3;
+ vuc32 RESP4;
+ vu32 DTIMER;
+ vu32 DLEN;
+ vu32 DCTRL;
+ vuc32 DCOUNT;
+ vuc32 STA;
+ vu32 ICR;
+ vu32 MASK;
+ u32 RESERVED0[2];
+ vuc32 FIFOCNT;
+ u32 RESERVED1[13];
+ vu32 FIFO;
+} SDIO_TypeDef;
+
+/*------------------------ Serial Peripheral Interface -----------------------*/
+typedef struct
+{
+ vu16 CR1;
+ u16 RESERVED0;
+ vu16 CR2;
+ u16 RESERVED1;
+ vu16 SR;
+ u16 RESERVED2;
+ vu16 DR;
+ u16 RESERVED3;
+ vu16 CRCPR;
+ u16 RESERVED4;
+ vu16 RXCRCR;
+ u16 RESERVED5;
+ vu16 TXCRCR;
+ u16 RESERVED6;
+ vu16 I2SCFGR;
+ u16 RESERVED7;
+ vu16 I2SPR;
+ u16 RESERVED8;
+} SPI_TypeDef;
+
+/*------------------------ SystemTick ----------------------------------------*/
+typedef struct
+{
+ vu32 CTRL;
+ vu32 LOAD;
+ vu32 VAL;
+ vuc32 CALIB;
+} SysTick_TypeDef;
+
+/*------------------------ TIM -----------------------------------------------*/
+typedef struct
+{
+ vu16 CR1;
+ u16 RESERVED0;
+ vu16 CR2;
+ u16 RESERVED1;
+ vu16 SMCR;
+ u16 RESERVED2;
+ vu16 DIER;
+ u16 RESERVED3;
+ vu16 SR;
+ u16 RESERVED4;
+ vu16 EGR;
+ u16 RESERVED5;
+ vu16 CCMR1;
+ u16 RESERVED6;
+ vu16 CCMR2;
+ u16 RESERVED7;
+ vu16 CCER;
+ u16 RESERVED8;
+ vu16 CNT;
+ u16 RESERVED9;
+ vu16 PSC;
+ u16 RESERVED10;
+ vu16 ARR;
+ u16 RESERVED11;
+ vu16 RCR;
+ u16 RESERVED12;
+ vu16 CCR1;
+ u16 RESERVED13;
+ vu16 CCR2;
+ u16 RESERVED14;
+ vu16 CCR3;
+ u16 RESERVED15;
+ vu16 CCR4;
+ u16 RESERVED16;
+ vu16 BDTR;
+ u16 RESERVED17;
+ vu16 DCR;
+ u16 RESERVED18;
+ vu16 DMAR;
+ u16 RESERVED19;
+} TIM_TypeDef;
+
+/*----------------- Universal Synchronous Asynchronous Receiver Transmitter --*/
+typedef struct
+{
+ vu16 SR;
+ u16 RESERVED0;
+ vu16 DR;
+ u16 RESERVED1;
+ vu16 BRR;
+ u16 RESERVED2;
+ vu16 CR1;
+ u16 RESERVED3;
+ vu16 CR2;
+ u16 RESERVED4;
+ vu16 CR3;
+ u16 RESERVED5;
+ vu16 GTPR;
+ u16 RESERVED6;
+} USART_TypeDef;
+
+/*------------------------ Window WATCHDOG -----------------------------------*/
+typedef struct
+{
+ vu32 CR;
+ vu32 CFR;
+ vu32 SR;
+} WWDG_TypeDef;
+
+/******************************************************************************/
+/* Peripheral memory map */
+/******************************************************************************/
+/* Peripheral and SRAM base address in the alias region */
+#define PERIPH_BB_BASE ((u32)0x42000000)
+#define SRAM_BB_BASE ((u32)0x22000000)
+
+/* Peripheral and SRAM base address in the bit-band region */
+#define SRAM_BASE ((u32)0x20000000)
+#define PERIPH_BASE ((u32)0x40000000)
+
+/* FSMC registers base address */
+#define FSMC_R_BASE ((u32)0xA0000000)
+
+/* Peripheral memory map */
+#define APB1PERIPH_BASE PERIPH_BASE
+#define APB2PERIPH_BASE (PERIPH_BASE + 0x10000)
+#define AHBPERIPH_BASE (PERIPH_BASE + 0x20000)
+
+#define TIM2_BASE (APB1PERIPH_BASE + 0x0000)
+#define TIM3_BASE (APB1PERIPH_BASE + 0x0400)
+#define TIM4_BASE (APB1PERIPH_BASE + 0x0800)
+#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00)
+#define TIM6_BASE (APB1PERIPH_BASE + 0x1000)
+#define TIM7_BASE (APB1PERIPH_BASE + 0x1400)
+#define RTC_BASE (APB1PERIPH_BASE + 0x2800)
+#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00)
+#define IWDG_BASE (APB1PERIPH_BASE + 0x3000)
+#define SPI2_BASE (APB1PERIPH_BASE + 0x3800)
+#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00)
+#define USART2_BASE (APB1PERIPH_BASE + 0x4400)
+#define USART3_BASE (APB1PERIPH_BASE + 0x4800)
+#define UART4_BASE (APB1PERIPH_BASE + 0x4C00)
+#define UART5_BASE (APB1PERIPH_BASE + 0x5000)
+#define I2C1_BASE (APB1PERIPH_BASE + 0x5400)
+#define I2C2_BASE (APB1PERIPH_BASE + 0x5800)
+#define CAN_BASE (APB1PERIPH_BASE + 0x6400)
+#define BKP_BASE (APB1PERIPH_BASE + 0x6C00)
+#define PWR_BASE (APB1PERIPH_BASE + 0x7000)
+#define DAC_BASE (APB1PERIPH_BASE + 0x7400)
+
+#define AFIO_BASE (APB2PERIPH_BASE + 0x0000)
+#define EXTI_BASE (APB2PERIPH_BASE + 0x0400)
+#define GPIOA_BASE (APB2PERIPH_BASE + 0x0800)
+#define GPIOB_BASE (APB2PERIPH_BASE + 0x0C00)
+#define GPIOC_BASE (APB2PERIPH_BASE + 0x1000)
+#define GPIOD_BASE (APB2PERIPH_BASE + 0x1400)
+#define GPIOE_BASE (APB2PERIPH_BASE + 0x1800)
+#define GPIOF_BASE (APB2PERIPH_BASE + 0x1C00)
+#define GPIOG_BASE (APB2PERIPH_BASE + 0x2000)
+#define ADC1_BASE (APB2PERIPH_BASE + 0x2400)
+#define ADC2_BASE (APB2PERIPH_BASE + 0x2800)
+#define TIM1_BASE (APB2PERIPH_BASE + 0x2C00)
+#define SPI1_BASE (APB2PERIPH_BASE + 0x3000)
+#define TIM8_BASE (APB2PERIPH_BASE + 0x3400)
+#define USART1_BASE (APB2PERIPH_BASE + 0x3800)
+#define ADC3_BASE (APB2PERIPH_BASE + 0x3C00)
+
+#define SDIO_BASE (PERIPH_BASE + 0x18000)
+
+#define DMA1_BASE (AHBPERIPH_BASE + 0x0000)
+#define DMA1_Channel1_BASE (AHBPERIPH_BASE + 0x0008)
+#define DMA1_Channel2_BASE (AHBPERIPH_BASE + 0x001C)
+#define DMA1_Channel3_BASE (AHBPERIPH_BASE + 0x0030)
+#define DMA1_Channel4_BASE (AHBPERIPH_BASE + 0x0044)
+#define DMA1_Channel5_BASE (AHBPERIPH_BASE + 0x0058)
+#define DMA1_Channel6_BASE (AHBPERIPH_BASE + 0x006C)
+#define DMA1_Channel7_BASE (AHBPERIPH_BASE + 0x0080)
+#define DMA2_BASE (AHBPERIPH_BASE + 0x0400)
+#define DMA2_Channel1_BASE (AHBPERIPH_BASE + 0x0408)
+#define DMA2_Channel2_BASE (AHBPERIPH_BASE + 0x041C)
+#define DMA2_Channel3_BASE (AHBPERIPH_BASE + 0x0430)
+#define DMA2_Channel4_BASE (AHBPERIPH_BASE + 0x0444)
+#define DMA2_Channel5_BASE (AHBPERIPH_BASE + 0x0458)
+#define RCC_BASE (AHBPERIPH_BASE + 0x1000)
+#define CRC_BASE (AHBPERIPH_BASE + 0x3000)
+
+/* Flash registers base address */
+#define FLASH_R_BASE (AHBPERIPH_BASE + 0x2000)
+/* Flash Option Bytes base address */
+#define OB_BASE ((u32)0x1FFFF800)
+
+/* FSMC Bankx registers base address */
+#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000)
+#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104)
+#define FSMC_Bank2_R_BASE (FSMC_R_BASE + 0x0060)
+#define FSMC_Bank3_R_BASE (FSMC_R_BASE + 0x0080)
+#define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0)
+
+/* Debug MCU registers base address */
+#define DBGMCU_BASE ((u32)0xE0042000)
+
+/* System Control Space memory map */
+#define SCS_BASE ((u32)0xE000E000)
+
+#define SysTick_BASE (SCS_BASE + 0x0010)
+#define NVIC_BASE (SCS_BASE + 0x0100)
+#define SCB_BASE (SCS_BASE + 0x0D00)
+
+/******************************************************************************/
+/* Peripheral declaration */
+/******************************************************************************/
+
+/*------------------------ Non Debug Mode ------------------------------------*/
+#ifndef DEBUG
+#ifdef _TIM2
+ #define TIM2 ((TIM_TypeDef *) TIM2_BASE)
+#endif /*_TIM2 */
+
+#ifdef _TIM3
+ #define TIM3 ((TIM_TypeDef *) TIM3_BASE)
+#endif /*_TIM3 */
+
+#ifdef _TIM4
+ #define TIM4 ((TIM_TypeDef *) TIM4_BASE)
+#endif /*_TIM4 */
+
+#ifdef _TIM5
+ #define TIM5 ((TIM_TypeDef *) TIM5_BASE)
+#endif /*_TIM5 */
+
+#ifdef _TIM6
+ #define TIM6 ((TIM_TypeDef *) TIM6_BASE)
+#endif /*_TIM6 */
+
+#ifdef _TIM7
+ #define TIM7 ((TIM_TypeDef *) TIM7_BASE)
+#endif /*_TIM7 */
+
+#ifdef _RTC
+ #define RTC ((RTC_TypeDef *) RTC_BASE)
+#endif /*_RTC */
+
+#ifdef _WWDG
+ #define WWDG ((WWDG_TypeDef *) WWDG_BASE)
+#endif /*_WWDG */
+
+#ifdef _IWDG
+ #define IWDG ((IWDG_TypeDef *) IWDG_BASE)
+#endif /*_IWDG */
+
+#ifdef _SPI2
+ #define SPI2 ((SPI_TypeDef *) SPI2_BASE)
+#endif /*_SPI2 */
+
+#ifdef _SPI3
+ #define SPI3 ((SPI_TypeDef *) SPI3_BASE)
+#endif /*_SPI3 */
+
+#ifdef _USART2
+ #define USART2 ((USART_TypeDef *) USART2_BASE)
+#endif /*_USART2 */
+
+#ifdef _USART3
+ #define USART3 ((USART_TypeDef *) USART3_BASE)
+#endif /*_USART3 */
+
+#ifdef _UART4
+ #define UART4 ((USART_TypeDef *) UART4_BASE)
+#endif /*_UART4 */
+
+#ifdef _UART5
+ #define UART5 ((USART_TypeDef *) UART5_BASE)
+#endif /*_USART5 */
+
+#ifdef _I2C1
+ #define I2C1 ((I2C_TypeDef *) I2C1_BASE)
+#endif /*_I2C1 */
+
+#ifdef _I2C2
+ #define I2C2 ((I2C_TypeDef *) I2C2_BASE)
+#endif /*_I2C2 */
+
+#ifdef _CAN
+ #define CAN ((CAN_TypeDef *) CAN_BASE)
+#endif /*_CAN */
+
+#ifdef _BKP
+ #define BKP ((BKP_TypeDef *) BKP_BASE)
+#endif /*_BKP */
+
+#ifdef _PWR
+ #define PWR ((PWR_TypeDef *) PWR_BASE)
+#endif /*_PWR */
+
+#ifdef _DAC
+ #define DAC ((DAC_TypeDef *) DAC_BASE)
+#endif /*_DAC */
+
+#ifdef _AFIO
+ #define AFIO ((AFIO_TypeDef *) AFIO_BASE)
+#endif /*_AFIO */
+
+#ifdef _EXTI
+ #define EXTI ((EXTI_TypeDef *) EXTI_BASE)
+#endif /*_EXTI */
+
+#ifdef _GPIOA
+ #define GPIOA ((GPIO_TypeDef *) GPIOA_BASE)
+#endif /*_GPIOA */
+
+#ifdef _GPIOB
+ #define GPIOB ((GPIO_TypeDef *) GPIOB_BASE)
+#endif /*_GPIOB */
+
+#ifdef _GPIOC
+ #define GPIOC ((GPIO_TypeDef *) GPIOC_BASE)
+#endif /*_GPIOC */
+
+#ifdef _GPIOD
+ #define GPIOD ((GPIO_TypeDef *) GPIOD_BASE)
+#endif /*_GPIOD */
+
+#ifdef _GPIOE
+ #define GPIOE ((GPIO_TypeDef *) GPIOE_BASE)
+#endif /*_GPIOE */
+
+#ifdef _GPIOF
+ #define GPIOF ((GPIO_TypeDef *) GPIOF_BASE)
+#endif /*_GPIOF */
+
+#ifdef _GPIOG
+ #define GPIOG ((GPIO_TypeDef *) GPIOG_BASE)
+#endif /*_GPIOG */
+
+#ifdef _ADC1
+ #define ADC1 ((ADC_TypeDef *) ADC1_BASE)
+#endif /*_ADC1 */
+
+#ifdef _ADC2
+ #define ADC2 ((ADC_TypeDef *) ADC2_BASE)
+#endif /*_ADC2 */
+
+#ifdef _TIM1
+ #define TIM1 ((TIM_TypeDef *) TIM1_BASE)
+#endif /*_TIM1 */
+
+#ifdef _SPI1
+ #define SPI1 ((SPI_TypeDef *) SPI1_BASE)
+#endif /*_SPI1 */
+
+#ifdef _TIM8
+ #define TIM8 ((TIM_TypeDef *) TIM8_BASE)
+#endif /*_TIM8 */
+
+#ifdef _USART1
+ #define USART1 ((USART_TypeDef *) USART1_BASE)
+#endif /*_USART1 */
+
+#ifdef _ADC3
+ #define ADC3 ((ADC_TypeDef *) ADC3_BASE)
+#endif /*_ADC3 */
+
+#ifdef _SDIO
+ #define SDIO ((SDIO_TypeDef *) SDIO_BASE)
+#endif /*_SDIO */
+
+#ifdef _DMA
+ #define DMA1 ((DMA_TypeDef *) DMA1_BASE)
+ #define DMA2 ((DMA_TypeDef *) DMA2_BASE)
+#endif /*_DMA */
+
+#ifdef _DMA1_Channel1
+ #define DMA1_Channel1 ((DMA_Channel_TypeDef *) DMA1_Channel1_BASE)
+#endif /*_DMA1_Channel1 */
+
+#ifdef _DMA1_Channel2
+ #define DMA1_Channel2 ((DMA_Channel_TypeDef *) DMA1_Channel2_BASE)
+#endif /*_DMA1_Channel2 */
+
+#ifdef _DMA1_Channel3
+ #define DMA1_Channel3 ((DMA_Channel_TypeDef *) DMA1_Channel3_BASE)
+#endif /*_DMA1_Channel3 */
+
+#ifdef _DMA1_Channel4
+ #define DMA1_Channel4 ((DMA_Channel_TypeDef *) DMA1_Channel4_BASE)
+#endif /*_DMA1_Channel4 */
+
+#ifdef _DMA1_Channel5
+ #define DMA1_Channel5 ((DMA_Channel_TypeDef *) DMA1_Channel5_BASE)
+#endif /*_DMA1_Channel5 */
+
+#ifdef _DMA1_Channel6
+ #define DMA1_Channel6 ((DMA_Channel_TypeDef *) DMA1_Channel6_BASE)
+#endif /*_DMA1_Channel6 */
+
+#ifdef _DMA1_Channel7
+ #define DMA1_Channel7 ((DMA_Channel_TypeDef *) DMA1_Channel7_BASE)
+#endif /*_DMA1_Channel7 */
+
+#ifdef _DMA2_Channel1
+ #define DMA2_Channel1 ((DMA_Channel_TypeDef *) DMA2_Channel1_BASE)
+#endif /*_DMA2_Channel1 */
+
+#ifdef _DMA2_Channel2
+ #define DMA2_Channel2 ((DMA_Channel_TypeDef *) DMA2_Channel2_BASE)
+#endif /*_DMA2_Channel2 */
+
+#ifdef _DMA2_Channel3
+ #define DMA2_Channel3 ((DMA_Channel_TypeDef *) DMA2_Channel3_BASE)
+#endif /*_DMA2_Channel3 */
+
+#ifdef _DMA2_Channel4
+ #define DMA2_Channel4 ((DMA_Channel_TypeDef *) DMA2_Channel4_BASE)
+#endif /*_DMA2_Channel4 */
+
+#ifdef _DMA2_Channel5
+ #define DMA2_Channel5 ((DMA_Channel_TypeDef *) DMA2_Channel5_BASE)
+#endif /*_DMA2_Channel5 */
+
+#ifdef _RCC
+ #define RCC ((RCC_TypeDef *) RCC_BASE)
+#endif /*_RCC */
+
+#ifdef _CRC
+ #define CRC ((CRC_TypeDef *) CRC_BASE)
+#endif /*_CRC */
+
+#ifdef _FLASH
+ #define FLASH ((FLASH_TypeDef *) FLASH_R_BASE)
+ #define OB ((OB_TypeDef *) OB_BASE)
+#endif /*_FLASH */
+
+#ifdef _FSMC
+ #define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE)
+ #define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE)
+ #define FSMC_Bank2 ((FSMC_Bank2_TypeDef *) FSMC_Bank2_R_BASE)
+ #define FSMC_Bank3 ((FSMC_Bank3_TypeDef *) FSMC_Bank3_R_BASE)
+ #define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE)
+#endif /*_FSMC */
+
+#ifdef _DBGMCU
+ #define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE)
+#endif /*_DBGMCU */
+
+#ifdef _SysTick
+ #define SysTick ((SysTick_TypeDef *) SysTick_BASE)
+#endif /*_SysTick */
+
+#ifdef _NVIC
+ #define NVIC ((NVIC_TypeDef *) NVIC_BASE)
+ #define SCB ((SCB_TypeDef *) SCB_BASE)
+#endif /*_NVIC */
+
+/*------------------------ Debug Mode ----------------------------------------*/
+#else /* DEBUG */
+#ifdef _TIM2
+ EXT TIM_TypeDef *TIM2;
+#endif /*_TIM2 */
+
+#ifdef _TIM3
+ EXT TIM_TypeDef *TIM3;
+#endif /*_TIM3 */
+
+#ifdef _TIM4
+ EXT TIM_TypeDef *TIM4;
+#endif /*_TIM4 */
+
+#ifdef _TIM5
+ EXT TIM_TypeDef *TIM5;
+#endif /*_TIM5 */
+
+#ifdef _TIM6
+ EXT TIM_TypeDef *TIM6;
+#endif /*_TIM6 */
+
+#ifdef _TIM7
+ EXT TIM_TypeDef *TIM7;
+#endif /*_TIM7 */
+
+#ifdef _RTC
+ EXT RTC_TypeDef *RTC;
+#endif /*_RTC */
+
+#ifdef _WWDG
+ EXT WWDG_TypeDef *WWDG;
+#endif /*_WWDG */
+
+#ifdef _IWDG
+ EXT IWDG_TypeDef *IWDG;
+#endif /*_IWDG */
+
+#ifdef _SPI2
+ EXT SPI_TypeDef *SPI2;
+#endif /*_SPI2 */
+
+#ifdef _SPI3
+ EXT SPI_TypeDef *SPI3;
+#endif /*_SPI3 */
+
+#ifdef _USART2
+ EXT USART_TypeDef *USART2;
+#endif /*_USART2 */
+
+#ifdef _USART3
+ EXT USART_TypeDef *USART3;
+#endif /*_USART3 */
+
+#ifdef _UART4
+ EXT USART_TypeDef *UART4;
+#endif /*_UART4 */
+
+#ifdef _UART5
+ EXT USART_TypeDef *UART5;
+#endif /*_UART5 */
+
+#ifdef _I2C1
+ EXT I2C_TypeDef *I2C1;
+#endif /*_I2C1 */
+
+#ifdef _I2C2
+ EXT I2C_TypeDef *I2C2;
+#endif /*_I2C2 */
+
+#ifdef _CAN
+ EXT CAN_TypeDef *CAN;
+#endif /*_CAN */
+
+#ifdef _BKP
+ EXT BKP_TypeDef *BKP;
+#endif /*_BKP */
+
+#ifdef _PWR
+ EXT PWR_TypeDef *PWR;
+#endif /*_PWR */
+
+#ifdef _DAC
+ EXT DAC_TypeDef *DAC;
+#endif /*_DAC */
+
+#ifdef _AFIO
+ EXT AFIO_TypeDef *AFIO;
+#endif /*_AFIO */
+
+#ifdef _EXTI
+ EXT EXTI_TypeDef *EXTI;
+#endif /*_EXTI */
+
+#ifdef _GPIOA
+ EXT GPIO_TypeDef *GPIOA;
+#endif /*_GPIOA */
+
+#ifdef _GPIOB
+ EXT GPIO_TypeDef *GPIOB;
+#endif /*_GPIOB */
+
+#ifdef _GPIOC
+ EXT GPIO_TypeDef *GPIOC;
+#endif /*_GPIOC */
+
+#ifdef _GPIOD
+ EXT GPIO_TypeDef *GPIOD;
+#endif /*_GPIOD */
+
+#ifdef _GPIOE
+ EXT GPIO_TypeDef *GPIOE;
+#endif /*_GPIOE */
+
+#ifdef _GPIOF
+ EXT GPIO_TypeDef *GPIOF;
+#endif /*_GPIOF */
+
+#ifdef _GPIOG
+ EXT GPIO_TypeDef *GPIOG;
+#endif /*_GPIOG */
+
+#ifdef _ADC1
+ EXT ADC_TypeDef *ADC1;
+#endif /*_ADC1 */
+
+#ifdef _ADC2
+ EXT ADC_TypeDef *ADC2;
+#endif /*_ADC2 */
+
+#ifdef _TIM1
+ EXT TIM_TypeDef *TIM1;
+#endif /*_TIM1 */
+
+#ifdef _SPI1
+ EXT SPI_TypeDef *SPI1;
+#endif /*_SPI1 */
+
+#ifdef _TIM8
+ EXT TIM_TypeDef *TIM8;
+#endif /*_TIM8 */
+
+#ifdef _USART1
+ EXT USART_TypeDef *USART1;
+#endif /*_USART1 */
+
+#ifdef _ADC3
+ EXT ADC_TypeDef *ADC3;
+#endif /*_ADC3 */
+
+#ifdef _SDIO
+ EXT SDIO_TypeDef *SDIO;
+#endif /*_SDIO */
+
+#ifdef _DMA
+ EXT DMA_TypeDef *DMA1;
+ EXT DMA_TypeDef *DMA2;
+#endif /*_DMA */
+
+#ifdef _DMA1_Channel1
+ EXT DMA_Channel_TypeDef *DMA1_Channel1;
+#endif /*_DMA1_Channel1 */
+
+#ifdef _DMA1_Channel2
+ EXT DMA_Channel_TypeDef *DMA1_Channel2;
+#endif /*_DMA1_Channel2 */
+
+#ifdef _DMA1_Channel3
+ EXT DMA_Channel_TypeDef *DMA1_Channel3;
+#endif /*_DMA1_Channel3 */
+
+#ifdef _DMA1_Channel4
+ EXT DMA_Channel_TypeDef *DMA1_Channel4;
+#endif /*_DMA1_Channel4 */
+
+#ifdef _DMA1_Channel5
+ EXT DMA_Channel_TypeDef *DMA1_Channel5;
+#endif /*_DMA1_Channel5 */
+
+#ifdef _DMA1_Channel6
+ EXT DMA_Channel_TypeDef *DMA1_Channel6;
+#endif /*_DMA1_Channel6 */
+
+#ifdef _DMA1_Channel7
+ EXT DMA_Channel_TypeDef *DMA1_Channel7;
+#endif /*_DMA1_Channel7 */
+
+#ifdef _DMA2_Channel1
+ EXT DMA_Channel_TypeDef *DMA2_Channel1;
+#endif /*_DMA2_Channel1 */
+
+#ifdef _DMA2_Channel2
+ EXT DMA_Channel_TypeDef *DMA2_Channel2;
+#endif /*_DMA2_Channel2 */
+
+#ifdef _DMA2_Channel3
+ EXT DMA_Channel_TypeDef *DMA2_Channel3;
+#endif /*_DMA2_Channel3 */
+
+#ifdef _DMA2_Channel4
+ EXT DMA_Channel_TypeDef *DMA2_Channel4;
+#endif /*_DMA2_Channel4 */
+
+#ifdef _DMA2_Channel5
+ EXT DMA_Channel_TypeDef *DMA2_Channel5;
+#endif /*_DMA2_Channel5 */
+
+#ifdef _RCC
+ EXT RCC_TypeDef *RCC;
+#endif /*_RCC */
+
+#ifdef _CRC
+ EXT CRC_TypeDef *CRC;
+#endif /*_CRC */
+
+#ifdef _FLASH
+ EXT FLASH_TypeDef *FLASH;
+ EXT OB_TypeDef *OB;
+#endif /*_FLASH */
+
+#ifdef _FSMC
+ EXT FSMC_Bank1_TypeDef *FSMC_Bank1;
+ EXT FSMC_Bank1E_TypeDef *FSMC_Bank1E;
+ EXT FSMC_Bank2_TypeDef *FSMC_Bank2;
+ EXT FSMC_Bank3_TypeDef *FSMC_Bank3;
+ EXT FSMC_Bank4_TypeDef *FSMC_Bank4;
+#endif /*_FSMC */
+
+#ifdef _DBGMCU
+ EXT DBGMCU_TypeDef *DBGMCU;
+#endif /*_DBGMCU */
+
+#ifdef _SysTick
+ EXT SysTick_TypeDef *SysTick;
+#endif /*_SysTick */
+
+#ifdef _NVIC
+ EXT NVIC_TypeDef *NVIC;
+ EXT SCB_TypeDef *SCB;
+#endif /*_NVIC */
+
+#endif /* DEBUG */
+
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __STM32F10x_MAP_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_nvic.h b/src/stm32lib/inc/stm32f10x_nvic.h new file mode 100644 index 0000000..6a9815b --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_nvic.h @@ -0,0 +1,293 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_nvic.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* NVIC firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_NVIC_H
+#define __STM32F10x_NVIC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* NVIC Init Structure definition */
+typedef struct
+{
+ u8 NVIC_IRQChannel;
+ u8 NVIC_IRQChannelPreemptionPriority;
+ u8 NVIC_IRQChannelSubPriority;
+ FunctionalState NVIC_IRQChannelCmd;
+} NVIC_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+/* IRQ Channels --------------------------------------------------------------*/
+#define WWDG_IRQChannel ((u8)0x00) /* Window WatchDog Interrupt */
+#define PVD_IRQChannel ((u8)0x01) /* PVD through EXTI Line detection Interrupt */
+#define TAMPER_IRQChannel ((u8)0x02) /* Tamper Interrupt */
+#define RTC_IRQChannel ((u8)0x03) /* RTC global Interrupt */
+#define FLASH_IRQChannel ((u8)0x04) /* FLASH global Interrupt */
+#define RCC_IRQChannel ((u8)0x05) /* RCC global Interrupt */
+#define EXTI0_IRQChannel ((u8)0x06) /* EXTI Line0 Interrupt */
+#define EXTI1_IRQChannel ((u8)0x07) /* EXTI Line1 Interrupt */
+#define EXTI2_IRQChannel ((u8)0x08) /* EXTI Line2 Interrupt */
+#define EXTI3_IRQChannel ((u8)0x09) /* EXTI Line3 Interrupt */
+#define EXTI4_IRQChannel ((u8)0x0A) /* EXTI Line4 Interrupt */
+#define DMA1_Channel1_IRQChannel ((u8)0x0B) /* DMA1 Channel 1 global Interrupt */
+#define DMA1_Channel2_IRQChannel ((u8)0x0C) /* DMA1 Channel 2 global Interrupt */
+#define DMA1_Channel3_IRQChannel ((u8)0x0D) /* DMA1 Channel 3 global Interrupt */
+#define DMA1_Channel4_IRQChannel ((u8)0x0E) /* DMA1 Channel 4 global Interrupt */
+#define DMA1_Channel5_IRQChannel ((u8)0x0F) /* DMA1 Channel 5 global Interrupt */
+#define DMA1_Channel6_IRQChannel ((u8)0x10) /* DMA1 Channel 6 global Interrupt */
+#define DMA1_Channel7_IRQChannel ((u8)0x11) /* DMA1 Channel 7 global Interrupt */
+#define ADC1_2_IRQChannel ((u8)0x12) /* ADC1 et ADC2 global Interrupt */
+#define USB_HP_CAN_TX_IRQChannel ((u8)0x13) /* USB High Priority or CAN TX Interrupts */
+#define USB_LP_CAN_RX0_IRQChannel ((u8)0x14) /* USB Low Priority or CAN RX0 Interrupts */
+#define CAN_RX1_IRQChannel ((u8)0x15) /* CAN RX1 Interrupt */
+#define CAN_SCE_IRQChannel ((u8)0x16) /* CAN SCE Interrupt */
+#define EXTI9_5_IRQChannel ((u8)0x17) /* External Line[9:5] Interrupts */
+#define TIM1_BRK_IRQChannel ((u8)0x18) /* TIM1 Break Interrupt */
+#define TIM1_UP_IRQChannel ((u8)0x19) /* TIM1 Update Interrupt */
+#define TIM1_TRG_COM_IRQChannel ((u8)0x1A) /* TIM1 Trigger and Commutation Interrupt */
+#define TIM1_CC_IRQChannel ((u8)0x1B) /* TIM1 Capture Compare Interrupt */
+#define TIM2_IRQChannel ((u8)0x1C) /* TIM2 global Interrupt */
+#define TIM3_IRQChannel ((u8)0x1D) /* TIM3 global Interrupt */
+#define TIM4_IRQChannel ((u8)0x1E) /* TIM4 global Interrupt */
+#define I2C1_EV_IRQChannel ((u8)0x1F) /* I2C1 Event Interrupt */
+#define I2C1_ER_IRQChannel ((u8)0x20) /* I2C1 Error Interrupt */
+#define I2C2_EV_IRQChannel ((u8)0x21) /* I2C2 Event Interrupt */
+#define I2C2_ER_IRQChannel ((u8)0x22) /* I2C2 Error Interrupt */
+#define SPI1_IRQChannel ((u8)0x23) /* SPI1 global Interrupt */
+#define SPI2_IRQChannel ((u8)0x24) /* SPI2 global Interrupt */
+#define USART1_IRQChannel ((u8)0x25) /* USART1 global Interrupt */
+#define USART2_IRQChannel ((u8)0x26) /* USART2 global Interrupt */
+#define USART3_IRQChannel ((u8)0x27) /* USART3 global Interrupt */
+#define EXTI15_10_IRQChannel ((u8)0x28) /* External Line[15:10] Interrupts */
+#define RTCAlarm_IRQChannel ((u8)0x29) /* RTC Alarm through EXTI Line Interrupt */
+#define USBWakeUp_IRQChannel ((u8)0x2A) /* USB WakeUp from suspend through EXTI Line Interrupt */
+#define TIM8_BRK_IRQChannel ((u8)0x2B) /* TIM8 Break Interrupt */
+#define TIM8_UP_IRQChannel ((u8)0x2C) /* TIM8 Update Interrupt */
+#define TIM8_TRG_COM_IRQChannel ((u8)0x2D) /* TIM8 Trigger and Commutation Interrupt */
+#define TIM8_CC_IRQChannel ((u8)0x2E) /* TIM8 Capture Compare Interrupt */
+#define ADC3_IRQChannel ((u8)0x2F) /* ADC3 global Interrupt */
+#define FSMC_IRQChannel ((u8)0x30) /* FSMC global Interrupt */
+#define SDIO_IRQChannel ((u8)0x31) /* SDIO global Interrupt */
+#define TIM5_IRQChannel ((u8)0x32) /* TIM5 global Interrupt */
+#define SPI3_IRQChannel ((u8)0x33) /* SPI3 global Interrupt */
+#define UART4_IRQChannel ((u8)0x34) /* UART4 global Interrupt */
+#define UART5_IRQChannel ((u8)0x35) /* UART5 global Interrupt */
+#define TIM6_IRQChannel ((u8)0x36) /* TIM6 global Interrupt */
+#define TIM7_IRQChannel ((u8)0x37) /* TIM7 global Interrupt */
+#define DMA2_Channel1_IRQChannel ((u8)0x38) /* DMA2 Channel 1 global Interrupt */
+#define DMA2_Channel2_IRQChannel ((u8)0x39) /* DMA2 Channel 2 global Interrupt */
+#define DMA2_Channel3_IRQChannel ((u8)0x3A) /* DMA2 Channel 3 global Interrupt */
+#define DMA2_Channel4_5_IRQChannel ((u8)0x3B) /* DMA2 Channel 4 and DMA2 Channel 5 global Interrupt */
+
+
+#define IS_NVIC_IRQ_CHANNEL(CHANNEL) (((CHANNEL) == WWDG_IRQChannel) || \
+ ((CHANNEL) == PVD_IRQChannel) || \
+ ((CHANNEL) == TAMPER_IRQChannel) || \
+ ((CHANNEL) == RTC_IRQChannel) || \
+ ((CHANNEL) == FLASH_IRQChannel) || \
+ ((CHANNEL) == RCC_IRQChannel) || \
+ ((CHANNEL) == EXTI0_IRQChannel) || \
+ ((CHANNEL) == EXTI1_IRQChannel) || \
+ ((CHANNEL) == EXTI2_IRQChannel) || \
+ ((CHANNEL) == EXTI3_IRQChannel) || \
+ ((CHANNEL) == EXTI4_IRQChannel) || \
+ ((CHANNEL) == DMA1_Channel1_IRQChannel) || \
+ ((CHANNEL) == DMA1_Channel2_IRQChannel) || \
+ ((CHANNEL) == DMA1_Channel3_IRQChannel) || \
+ ((CHANNEL) == DMA1_Channel4_IRQChannel) || \
+ ((CHANNEL) == DMA1_Channel5_IRQChannel) || \
+ ((CHANNEL) == DMA1_Channel6_IRQChannel) || \
+ ((CHANNEL) == DMA1_Channel7_IRQChannel) || \
+ ((CHANNEL) == ADC1_2_IRQChannel) || \
+ ((CHANNEL) == USB_HP_CAN_TX_IRQChannel) || \
+ ((CHANNEL) == USB_LP_CAN_RX0_IRQChannel) || \
+ ((CHANNEL) == CAN_RX1_IRQChannel) || \
+ ((CHANNEL) == CAN_SCE_IRQChannel) || \
+ ((CHANNEL) == EXTI9_5_IRQChannel) || \
+ ((CHANNEL) == TIM1_BRK_IRQChannel) || \
+ ((CHANNEL) == TIM1_UP_IRQChannel) || \
+ ((CHANNEL) == TIM1_TRG_COM_IRQChannel) || \
+ ((CHANNEL) == TIM1_CC_IRQChannel) || \
+ ((CHANNEL) == TIM2_IRQChannel) || \
+ ((CHANNEL) == TIM3_IRQChannel) || \
+ ((CHANNEL) == TIM4_IRQChannel) || \
+ ((CHANNEL) == I2C1_EV_IRQChannel) || \
+ ((CHANNEL) == I2C1_ER_IRQChannel) || \
+ ((CHANNEL) == I2C2_EV_IRQChannel) || \
+ ((CHANNEL) == I2C2_ER_IRQChannel) || \
+ ((CHANNEL) == SPI1_IRQChannel) || \
+ ((CHANNEL) == SPI2_IRQChannel) || \
+ ((CHANNEL) == USART1_IRQChannel) || \
+ ((CHANNEL) == USART2_IRQChannel) || \
+ ((CHANNEL) == USART3_IRQChannel) || \
+ ((CHANNEL) == EXTI15_10_IRQChannel) || \
+ ((CHANNEL) == RTCAlarm_IRQChannel) || \
+ ((CHANNEL) == USBWakeUp_IRQChannel) || \
+ ((CHANNEL) == TIM8_BRK_IRQChannel) || \
+ ((CHANNEL) == TIM8_UP_IRQChannel) || \
+ ((CHANNEL) == TIM8_TRG_COM_IRQChannel) || \
+ ((CHANNEL) == TIM8_CC_IRQChannel) || \
+ ((CHANNEL) == ADC3_IRQChannel) || \
+ ((CHANNEL) == FSMC_IRQChannel) || \
+ ((CHANNEL) == SDIO_IRQChannel) || \
+ ((CHANNEL) == TIM5_IRQChannel) || \
+ ((CHANNEL) == SPI3_IRQChannel) || \
+ ((CHANNEL) == UART4_IRQChannel) || \
+ ((CHANNEL) == UART5_IRQChannel) || \
+ ((CHANNEL) == TIM6_IRQChannel) || \
+ ((CHANNEL) == TIM7_IRQChannel) || \
+ ((CHANNEL) == DMA2_Channel1_IRQChannel) || \
+ ((CHANNEL) == DMA2_Channel2_IRQChannel) || \
+ ((CHANNEL) == DMA2_Channel3_IRQChannel) || \
+ ((CHANNEL) == DMA2_Channel4_5_IRQChannel))
+
+
+/* System Handlers -----------------------------------------------------------*/
+#define SystemHandler_NMI ((u32)0x00001F) /* NMI Handler */
+#define SystemHandler_HardFault ((u32)0x000000) /* Hard Fault Handler */
+#define SystemHandler_MemoryManage ((u32)0x043430) /* Memory Manage Handler */
+#define SystemHandler_BusFault ((u32)0x547931) /* Bus Fault Handler */
+#define SystemHandler_UsageFault ((u32)0x24C232) /* Usage Fault Handler */
+#define SystemHandler_SVCall ((u32)0x01FF40) /* SVCall Handler */
+#define SystemHandler_DebugMonitor ((u32)0x0A0080) /* Debug Monitor Handler */
+#define SystemHandler_PSV ((u32)0x02829C) /* PSV Handler */
+#define SystemHandler_SysTick ((u32)0x02C39A) /* SysTick Handler */
+
+#define IS_CONFIG_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_MemoryManage) || \
+ ((HANDLER) == SystemHandler_BusFault) || \
+ ((HANDLER) == SystemHandler_UsageFault))
+
+#define IS_PRIORITY_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_MemoryManage) || \
+ ((HANDLER) == SystemHandler_BusFault) || \
+ ((HANDLER) == SystemHandler_UsageFault) || \
+ ((HANDLER) == SystemHandler_SVCall) || \
+ ((HANDLER) == SystemHandler_DebugMonitor) || \
+ ((HANDLER) == SystemHandler_PSV) || \
+ ((HANDLER) == SystemHandler_SysTick))
+
+#define IS_GET_PENDING_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_MemoryManage) || \
+ ((HANDLER) == SystemHandler_BusFault) || \
+ ((HANDLER) == SystemHandler_SVCall))
+
+#define IS_SET_PENDING_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_NMI) || \
+ ((HANDLER) == SystemHandler_PSV) || \
+ ((HANDLER) == SystemHandler_SysTick))
+
+#define IS_CLEAR_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_PSV) || \
+ ((HANDLER) == SystemHandler_SysTick))
+
+#define IS_GET_ACTIVE_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_MemoryManage) || \
+ ((HANDLER) == SystemHandler_BusFault) || \
+ ((HANDLER) == SystemHandler_UsageFault) || \
+ ((HANDLER) == SystemHandler_SVCall) || \
+ ((HANDLER) == SystemHandler_DebugMonitor) || \
+ ((HANDLER) == SystemHandler_PSV) || \
+ ((HANDLER) == SystemHandler_SysTick))
+
+#define IS_FAULT_SOURCE_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_HardFault) || \
+ ((HANDLER) == SystemHandler_MemoryManage) || \
+ ((HANDLER) == SystemHandler_BusFault) || \
+ ((HANDLER) == SystemHandler_UsageFault) || \
+ ((HANDLER) == SystemHandler_DebugMonitor))
+
+#define IS_FAULT_ADDRESS_SYSTEM_HANDLER(HANDLER) (((HANDLER) == SystemHandler_MemoryManage) || \
+ ((HANDLER) == SystemHandler_BusFault))
+
+
+/* Vector Table Base ---------------------------------------------------------*/
+#define NVIC_VectTab_RAM ((u32)0x20000000)
+#define NVIC_VectTab_FLASH ((u32)0x08000000)
+
+#define IS_NVIC_VECTTAB(VECTTAB) (((VECTTAB) == NVIC_VectTab_RAM) || \
+ ((VECTTAB) == NVIC_VectTab_FLASH))
+
+/* System Low Power ----------------------------------------------------------*/
+#define NVIC_LP_SEVONPEND ((u8)0x10)
+#define NVIC_LP_SLEEPDEEP ((u8)0x04)
+#define NVIC_LP_SLEEPONEXIT ((u8)0x02)
+
+#define IS_NVIC_LP(LP) (((LP) == NVIC_LP_SEVONPEND) || \
+ ((LP) == NVIC_LP_SLEEPDEEP) || \
+ ((LP) == NVIC_LP_SLEEPONEXIT))
+
+/* Preemption Priority Group -------------------------------------------------*/
+#define NVIC_PriorityGroup_0 ((u32)0x700) /* 0 bits for pre-emption priority
+ 4 bits for subpriority */
+#define NVIC_PriorityGroup_1 ((u32)0x600) /* 1 bits for pre-emption priority
+ 3 bits for subpriority */
+#define NVIC_PriorityGroup_2 ((u32)0x500) /* 2 bits for pre-emption priority
+ 2 bits for subpriority */
+#define NVIC_PriorityGroup_3 ((u32)0x400) /* 3 bits for pre-emption priority
+ 1 bits for subpriority */
+#define NVIC_PriorityGroup_4 ((u32)0x300) /* 4 bits for pre-emption priority
+ 0 bits for subpriority */
+
+#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PriorityGroup_0) || \
+ ((GROUP) == NVIC_PriorityGroup_1) || \
+ ((GROUP) == NVIC_PriorityGroup_2) || \
+ ((GROUP) == NVIC_PriorityGroup_3) || \
+ ((GROUP) == NVIC_PriorityGroup_4))
+
+#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x10)
+#define IS_NVIC_SUB_PRIORITY(PRIORITY) ((PRIORITY) < 0x10)
+#define IS_NVIC_OFFSET(OFFSET) ((OFFSET) < 0x0007FFFF)
+#define IS_NVIC_BASE_PRI(PRI) ((PRI) < 0x10)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+#ifdef __cplusplus
+extern "C" {
+#endif
+void NVIC_DeInit(void);
+void NVIC_SCBDeInit(void);
+void NVIC_PriorityGroupConfig(u32 NVIC_PriorityGroup);
+void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct);
+void NVIC_StructInit(NVIC_InitTypeDef* NVIC_InitStruct);
+void NVIC_SETPRIMASK(void);
+void NVIC_RESETPRIMASK(void);
+void NVIC_SETFAULTMASK(void);
+void NVIC_RESETFAULTMASK(void);
+void NVIC_BASEPRICONFIG(u32 NewPriority);
+u32 NVIC_GetBASEPRI(void);
+u16 NVIC_GetCurrentPendingIRQChannel(void);
+ITStatus NVIC_GetIRQChannelPendingBitStatus(u8 NVIC_IRQChannel);
+void NVIC_SetIRQChannelPendingBit(u8 NVIC_IRQChannel);
+void NVIC_ClearIRQChannelPendingBit(u8 NVIC_IRQChannel);
+u16 NVIC_GetCurrentActiveHandler(void);
+ITStatus NVIC_GetIRQChannelActiveBitStatus(u8 NVIC_IRQChannel);
+u32 NVIC_GetCPUID(void);
+void NVIC_SetVectorTable(u32 NVIC_VectTab, u32 Offset);
+void NVIC_GenerateSystemReset(void);
+void NVIC_GenerateCoreReset(void);
+void NVIC_SystemLPConfig(u8 LowPowerMode, FunctionalState NewState);
+void NVIC_SystemHandlerConfig(u32 SystemHandler, FunctionalState NewState);
+void NVIC_SystemHandlerPriorityConfig(u32 SystemHandler, u8 SystemHandlerPreemptionPriority,
+ u8 SystemHandlerSubPriority);
+ITStatus NVIC_GetSystemHandlerPendingBitStatus(u32 SystemHandler);
+void NVIC_SetSystemHandlerPendingBit(u32 SystemHandler);
+void NVIC_ClearSystemHandlerPendingBit(u32 SystemHandler);
+ITStatus NVIC_GetSystemHandlerActiveBitStatus(u32 SystemHandler);
+u32 NVIC_GetFaultHandlerSources(u32 SystemHandler);
+u32 NVIC_GetFaultAddress(u32 SystemHandler);
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_NVIC_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_pwr.h b/src/stm32lib/inc/stm32f10x_pwr.h new file mode 100644 index 0000000..ffcc438 --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_pwr.h @@ -0,0 +1,77 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_pwr.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* PWR firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_PWR_H
+#define __STM32F10x_PWR_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* PVD detection level */
+#define PWR_PVDLevel_2V2 ((u32)0x00000000)
+#define PWR_PVDLevel_2V3 ((u32)0x00000020)
+#define PWR_PVDLevel_2V4 ((u32)0x00000040)
+#define PWR_PVDLevel_2V5 ((u32)0x00000060)
+#define PWR_PVDLevel_2V6 ((u32)0x00000080)
+#define PWR_PVDLevel_2V7 ((u32)0x000000A0)
+#define PWR_PVDLevel_2V8 ((u32)0x000000C0)
+#define PWR_PVDLevel_2V9 ((u32)0x000000E0)
+
+#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLevel_2V2) || ((LEVEL) == PWR_PVDLevel_2V3)|| \
+ ((LEVEL) == PWR_PVDLevel_2V4) || ((LEVEL) == PWR_PVDLevel_2V5)|| \
+ ((LEVEL) == PWR_PVDLevel_2V6) || ((LEVEL) == PWR_PVDLevel_2V7)|| \
+ ((LEVEL) == PWR_PVDLevel_2V8) || ((LEVEL) == PWR_PVDLevel_2V9))
+
+/* Regulator state is STOP mode */
+#define PWR_Regulator_ON ((u32)0x00000000)
+#define PWR_Regulator_LowPower ((u32)0x00000001)
+
+#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_Regulator_ON) || \
+ ((REGULATOR) == PWR_Regulator_LowPower))
+
+/* STOP mode entry */
+#define PWR_STOPEntry_WFI ((u8)0x01)
+#define PWR_STOPEntry_WFE ((u8)0x02)
+
+#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPEntry_WFI) || ((ENTRY) == PWR_STOPEntry_WFE))
+
+/* PWR Flag */
+#define PWR_FLAG_WU ((u32)0x00000001)
+#define PWR_FLAG_SB ((u32)0x00000002)
+#define PWR_FLAG_PVDO ((u32)0x00000004)
+
+#define IS_PWR_GET_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB) || \
+ ((FLAG) == PWR_FLAG_PVDO))
+#define IS_PWR_CLEAR_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void PWR_DeInit(void);
+void PWR_BackupAccessCmd(FunctionalState NewState);
+void PWR_PVDCmd(FunctionalState NewState);
+void PWR_PVDLevelConfig(u32 PWR_PVDLevel);
+void PWR_WakeUpPinCmd(FunctionalState NewState);
+void PWR_EnterSTOPMode(u32 PWR_Regulator, u8 PWR_STOPEntry);
+void PWR_EnterSTANDBYMode(void);
+FlagStatus PWR_GetFlagStatus(u32 PWR_FLAG);
+void PWR_ClearFlag(u32 PWR_FLAG);
+
+#endif /* __STM32F10x_PWR_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_rcc.h b/src/stm32lib/inc/stm32f10x_rcc.h new file mode 100644 index 0000000..f0c39d7 --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_rcc.h @@ -0,0 +1,295 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_rcc.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* RCC firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_RCC_H
+#define __STM32F10x_RCC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+typedef struct
+{
+ u32 SYSCLK_Frequency;
+ u32 HCLK_Frequency;
+ u32 PCLK1_Frequency;
+ u32 PCLK2_Frequency;
+ u32 ADCCLK_Frequency;
+}RCC_ClocksTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+/* HSE configuration */
+#define RCC_HSE_OFF ((u32)0x00000000)
+#define RCC_HSE_ON ((u32)0x00010000)
+#define RCC_HSE_Bypass ((u32)0x00040000)
+
+#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \
+ ((HSE) == RCC_HSE_Bypass))
+
+/* PLL entry clock source */
+#define RCC_PLLSource_HSI_Div2 ((u32)0x00000000)
+#define RCC_PLLSource_HSE_Div1 ((u32)0x00010000)
+#define RCC_PLLSource_HSE_Div2 ((u32)0x00030000)
+
+#define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \
+ ((SOURCE) == RCC_PLLSource_HSE_Div1) || \
+ ((SOURCE) == RCC_PLLSource_HSE_Div2))
+
+/* PLL multiplication factor */
+#define RCC_PLLMul_2 ((u32)0x00000000)
+#define RCC_PLLMul_3 ((u32)0x00040000)
+#define RCC_PLLMul_4 ((u32)0x00080000)
+#define RCC_PLLMul_5 ((u32)0x000C0000)
+#define RCC_PLLMul_6 ((u32)0x00100000)
+#define RCC_PLLMul_7 ((u32)0x00140000)
+#define RCC_PLLMul_8 ((u32)0x00180000)
+#define RCC_PLLMul_9 ((u32)0x001C0000)
+#define RCC_PLLMul_10 ((u32)0x00200000)
+#define RCC_PLLMul_11 ((u32)0x00240000)
+#define RCC_PLLMul_12 ((u32)0x00280000)
+#define RCC_PLLMul_13 ((u32)0x002C0000)
+#define RCC_PLLMul_14 ((u32)0x00300000)
+#define RCC_PLLMul_15 ((u32)0x00340000)
+#define RCC_PLLMul_16 ((u32)0x00380000)
+
+#define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_2) || ((MUL) == RCC_PLLMul_3) || \
+ ((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \
+ ((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \
+ ((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \
+ ((MUL) == RCC_PLLMul_10) || ((MUL) == RCC_PLLMul_11) || \
+ ((MUL) == RCC_PLLMul_12) || ((MUL) == RCC_PLLMul_13) || \
+ ((MUL) == RCC_PLLMul_14) || ((MUL) == RCC_PLLMul_15) || \
+ ((MUL) == RCC_PLLMul_16))
+
+/* System clock source */
+#define RCC_SYSCLKSource_HSI ((u32)0x00000000)
+#define RCC_SYSCLKSource_HSE ((u32)0x00000001)
+#define RCC_SYSCLKSource_PLLCLK ((u32)0x00000002)
+
+#define IS_RCC_SYSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSource_HSI) || \
+ ((SOURCE) == RCC_SYSCLKSource_HSE) || \
+ ((SOURCE) == RCC_SYSCLKSource_PLLCLK))
+
+/* AHB clock source */
+#define RCC_SYSCLK_Div1 ((u32)0x00000000)
+#define RCC_SYSCLK_Div2 ((u32)0x00000080)
+#define RCC_SYSCLK_Div4 ((u32)0x00000090)
+#define RCC_SYSCLK_Div8 ((u32)0x000000A0)
+#define RCC_SYSCLK_Div16 ((u32)0x000000B0)
+#define RCC_SYSCLK_Div64 ((u32)0x000000C0)
+#define RCC_SYSCLK_Div128 ((u32)0x000000D0)
+#define RCC_SYSCLK_Div256 ((u32)0x000000E0)
+#define RCC_SYSCLK_Div512 ((u32)0x000000F0)
+
+#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_Div1) || ((HCLK) == RCC_SYSCLK_Div2) || \
+ ((HCLK) == RCC_SYSCLK_Div4) || ((HCLK) == RCC_SYSCLK_Div8) || \
+ ((HCLK) == RCC_SYSCLK_Div16) || ((HCLK) == RCC_SYSCLK_Div64) || \
+ ((HCLK) == RCC_SYSCLK_Div128) || ((HCLK) == RCC_SYSCLK_Div256) || \
+ ((HCLK) == RCC_SYSCLK_Div512))
+
+/* APB1/APB2 clock source */
+#define RCC_HCLK_Div1 ((u32)0x00000000)
+#define RCC_HCLK_Div2 ((u32)0x00000400)
+#define RCC_HCLK_Div4 ((u32)0x00000500)
+#define RCC_HCLK_Div8 ((u32)0x00000600)
+#define RCC_HCLK_Div16 ((u32)0x00000700)
+
+#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_Div1) || ((PCLK) == RCC_HCLK_Div2) || \
+ ((PCLK) == RCC_HCLK_Div4) || ((PCLK) == RCC_HCLK_Div8) || \
+ ((PCLK) == RCC_HCLK_Div16))
+
+/* RCC Interrupt source */
+#define RCC_IT_LSIRDY ((u8)0x01)
+#define RCC_IT_LSERDY ((u8)0x02)
+#define RCC_IT_HSIRDY ((u8)0x04)
+#define RCC_IT_HSERDY ((u8)0x08)
+#define RCC_IT_PLLRDY ((u8)0x10)
+#define RCC_IT_CSS ((u8)0x80)
+
+#define IS_RCC_IT(IT) ((((IT) & (u8)0xE0) == 0x00) && ((IT) != 0x00))
+#define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \
+ ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \
+ ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS))
+#define IS_RCC_CLEAR_IT(IT) ((((IT) & (u8)0x60) == 0x00) && ((IT) != 0x00))
+
+/* USB clock source */
+#define RCC_USBCLKSource_PLLCLK_1Div5 ((u8)0x00)
+#define RCC_USBCLKSource_PLLCLK_Div1 ((u8)0x01)
+
+#define IS_RCC_USBCLK_SOURCE(SOURCE) (((SOURCE) == RCC_USBCLKSource_PLLCLK_1Div5) || \
+ ((SOURCE) == RCC_USBCLKSource_PLLCLK_Div1))
+
+/* ADC clock source */
+#define RCC_PCLK2_Div2 ((u32)0x00000000)
+#define RCC_PCLK2_Div4 ((u32)0x00004000)
+#define RCC_PCLK2_Div6 ((u32)0x00008000)
+#define RCC_PCLK2_Div8 ((u32)0x0000C000)
+
+#define IS_RCC_ADCCLK(ADCCLK) (((ADCCLK) == RCC_PCLK2_Div2) || ((ADCCLK) == RCC_PCLK2_Div4) || \
+ ((ADCCLK) == RCC_PCLK2_Div6) || ((ADCCLK) == RCC_PCLK2_Div8))
+
+/* LSE configuration */
+#define RCC_LSE_OFF ((u8)0x00)
+#define RCC_LSE_ON ((u8)0x01)
+#define RCC_LSE_Bypass ((u8)0x04)
+
+#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \
+ ((LSE) == RCC_LSE_Bypass))
+
+/* RTC clock source */
+#define RCC_RTCCLKSource_LSE ((u32)0x00000100)
+#define RCC_RTCCLKSource_LSI ((u32)0x00000200)
+#define RCC_RTCCLKSource_HSE_Div128 ((u32)0x00000300)
+
+#define IS_RCC_RTCCLK_SOURCE(SOURCE) (((SOURCE) == RCC_RTCCLKSource_LSE) || \
+ ((SOURCE) == RCC_RTCCLKSource_LSI) || \
+ ((SOURCE) == RCC_RTCCLKSource_HSE_Div128))
+
+/* AHB peripheral */
+#define RCC_AHBPeriph_DMA1 ((u32)0x00000001)
+#define RCC_AHBPeriph_DMA2 ((u32)0x00000002)
+#define RCC_AHBPeriph_SRAM ((u32)0x00000004)
+#define RCC_AHBPeriph_FLITF ((u32)0x00000010)
+#define RCC_AHBPeriph_CRC ((u32)0x00000040)
+#define RCC_AHBPeriph_FSMC ((u32)0x00000100)
+#define RCC_AHBPeriph_SDIO ((u32)0x00000400)
+
+#define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFAA8) == 0x00) && ((PERIPH) != 0x00))
+
+/* APB2 peripheral */
+#define RCC_APB2Periph_AFIO ((u32)0x00000001)
+#define RCC_APB2Periph_GPIOA ((u32)0x00000004)
+#define RCC_APB2Periph_GPIOB ((u32)0x00000008)
+#define RCC_APB2Periph_GPIOC ((u32)0x00000010)
+#define RCC_APB2Periph_GPIOD ((u32)0x00000020)
+#define RCC_APB2Periph_GPIOE ((u32)0x00000040)
+#define RCC_APB2Periph_GPIOF ((u32)0x00000080)
+#define RCC_APB2Periph_GPIOG ((u32)0x00000100)
+#define RCC_APB2Periph_ADC1 ((u32)0x00000200)
+#define RCC_APB2Periph_ADC2 ((u32)0x00000400)
+#define RCC_APB2Periph_TIM1 ((u32)0x00000800)
+#define RCC_APB2Periph_SPI1 ((u32)0x00001000)
+#define RCC_APB2Periph_TIM8 ((u32)0x00002000)
+#define RCC_APB2Periph_USART1 ((u32)0x00004000)
+#define RCC_APB2Periph_ADC3 ((u32)0x00008000)
+#define RCC_APB2Periph_ALL ((u32)0x0000FFFD)
+
+#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xFFFF0002) == 0x00) && ((PERIPH) != 0x00))
+
+/* APB1 peripheral */
+#define RCC_APB1Periph_TIM2 ((u32)0x00000001)
+#define RCC_APB1Periph_TIM3 ((u32)0x00000002)
+#define RCC_APB1Periph_TIM4 ((u32)0x00000004)
+#define RCC_APB1Periph_TIM5 ((u32)0x00000008)
+#define RCC_APB1Periph_TIM6 ((u32)0x00000010)
+#define RCC_APB1Periph_TIM7 ((u32)0x00000020)
+#define RCC_APB1Periph_WWDG ((u32)0x00000800)
+#define RCC_APB1Periph_SPI2 ((u32)0x00004000)
+#define RCC_APB1Periph_SPI3 ((u32)0x00008000)
+#define RCC_APB1Periph_USART2 ((u32)0x00020000)
+#define RCC_APB1Periph_USART3 ((u32)0x00040000)
+#define RCC_APB1Periph_UART4 ((u32)0x00080000)
+#define RCC_APB1Periph_UART5 ((u32)0x00100000)
+#define RCC_APB1Periph_I2C1 ((u32)0x00200000)
+#define RCC_APB1Periph_I2C2 ((u32)0x00400000)
+#define RCC_APB1Periph_USB ((u32)0x00800000)
+#define RCC_APB1Periph_CAN ((u32)0x02000000)
+#define RCC_APB1Periph_BKP ((u32)0x08000000)
+#define RCC_APB1Periph_PWR ((u32)0x10000000)
+#define RCC_APB1Periph_DAC ((u32)0x20000000)
+#define RCC_APB1Periph_ALL ((u32)0x3AFEC83F)
+
+#define IS_RCC_APB1_PERIPH(PERIPH) ((((PERIPH) & 0xC50137C0) == 0x00) && ((PERIPH) != 0x00))
+
+/* Clock source to output on MCO pin */
+#define RCC_MCO_NoClock ((u8)0x00)
+#define RCC_MCO_SYSCLK ((u8)0x04)
+#define RCC_MCO_HSI ((u8)0x05)
+#define RCC_MCO_HSE ((u8)0x06)
+#define RCC_MCO_PLLCLK_Div2 ((u8)0x07)
+
+#define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \
+ ((MCO) == RCC_MCO_SYSCLK) || ((MCO) == RCC_MCO_HSE) || \
+ ((MCO) == RCC_MCO_PLLCLK_Div2))
+
+/* RCC Flag */
+#define RCC_FLAG_HSIRDY ((u8)0x20)
+#define RCC_FLAG_HSERDY ((u8)0x31)
+#define RCC_FLAG_PLLRDY ((u8)0x39)
+#define RCC_FLAG_LSERDY ((u8)0x41)
+#define RCC_FLAG_LSIRDY ((u8)0x61)
+#define RCC_FLAG_PINRST ((u8)0x7A)
+#define RCC_FLAG_PORRST ((u8)0x7B)
+#define RCC_FLAG_SFTRST ((u8)0x7C)
+#define RCC_FLAG_IWDGRST ((u8)0x7D)
+#define RCC_FLAG_WWDGRST ((u8)0x7E)
+#define RCC_FLAG_LPWRRST ((u8)0x7F)
+
+#define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \
+ ((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \
+ ((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \
+ ((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \
+ ((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \
+ ((FLAG) == RCC_FLAG_LPWRRST))
+
+#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1F)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void RCC_DeInit(void);
+void RCC_HSEConfig(u32 RCC_HSE);
+ErrorStatus RCC_WaitForHSEStartUp(void);
+void RCC_AdjustHSICalibrationValue(u8 HSICalibrationValue);
+void RCC_HSICmd(FunctionalState NewState);
+void RCC_PLLConfig(u32 RCC_PLLSource, u32 RCC_PLLMul);
+void RCC_PLLCmd(FunctionalState NewState);
+void RCC_SYSCLKConfig(u32 RCC_SYSCLKSource);
+u8 RCC_GetSYSCLKSource(void);
+void RCC_HCLKConfig(u32 RCC_SYSCLK);
+void RCC_PCLK1Config(u32 RCC_HCLK);
+void RCC_PCLK2Config(u32 RCC_HCLK);
+void RCC_ITConfig(u8 RCC_IT, FunctionalState NewState);
+void RCC_USBCLKConfig(u32 RCC_USBCLKSource);
+void RCC_ADCCLKConfig(u32 RCC_PCLK2);
+void RCC_LSEConfig(u8 RCC_LSE);
+void RCC_LSICmd(FunctionalState NewState);
+void RCC_RTCCLKConfig(u32 RCC_RTCCLKSource);
+void RCC_RTCCLKCmd(FunctionalState NewState);
+void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks);
+void RCC_AHBPeriphClockCmd(u32 RCC_AHBPeriph, FunctionalState NewState);
+void RCC_APB2PeriphClockCmd(u32 RCC_APB2Periph, FunctionalState NewState);
+void RCC_APB1PeriphClockCmd(u32 RCC_APB1Periph, FunctionalState NewState);
+void RCC_APB2PeriphResetCmd(u32 RCC_APB2Periph, FunctionalState NewState);
+void RCC_APB1PeriphResetCmd(u32 RCC_APB1Periph, FunctionalState NewState);
+void RCC_BackupResetCmd(FunctionalState NewState);
+void RCC_ClockSecuritySystemCmd(FunctionalState NewState);
+void RCC_MCOConfig(u8 RCC_MCO);
+FlagStatus RCC_GetFlagStatus(u8 RCC_FLAG);
+void RCC_ClearFlag(void);
+ITStatus RCC_GetITStatus(u8 RCC_IT);
+void RCC_ClearITPendingBit(u8 RCC_IT);
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_RCC_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_rtc.h b/src/stm32lib/inc/stm32f10x_rtc.h new file mode 100644 index 0000000..6ea7b78 --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_rtc.h @@ -0,0 +1,70 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_rtc.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* RTC firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_RTC_H
+#define __STM32F10x_RTC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* RTC interrupts define -----------------------------------------------------*/
+#define RTC_IT_OW ((u16)0x0004) /* Overflow interrupt */
+#define RTC_IT_ALR ((u16)0x0002) /* Alarm interrupt */
+#define RTC_IT_SEC ((u16)0x0001) /* Second interrupt */
+
+#define IS_RTC_IT(IT) ((((IT) & (u16)0xFFF8) == 0x00) && ((IT) != 0x00))
+
+#define IS_RTC_GET_IT(IT) (((IT) == RTC_IT_OW) || ((IT) == RTC_IT_ALR) || \
+ ((IT) == RTC_IT_SEC))
+
+/* RTC interrupts flags ------------------------------------------------------*/
+#define RTC_FLAG_RTOFF ((u16)0x0020) /* RTC Operation OFF flag */
+#define RTC_FLAG_RSF ((u16)0x0008) /* Registers Synchronized flag */
+#define RTC_FLAG_OW ((u16)0x0004) /* Overflow flag */
+#define RTC_FLAG_ALR ((u16)0x0002) /* Alarm flag */
+#define RTC_FLAG_SEC ((u16)0x0001) /* Second flag */
+
+#define IS_RTC_CLEAR_FLAG(FLAG) ((((FLAG) & (u16)0xFFF0) == 0x00) && ((FLAG) != 0x00))
+
+#define IS_RTC_GET_FLAG(FLAG) (((FLAG) == RTC_FLAG_RTOFF) || ((FLAG) == RTC_FLAG_RSF) || \
+ ((FLAG) == RTC_FLAG_OW) || ((FLAG) == RTC_FLAG_ALR) || \
+ ((FLAG) == RTC_FLAG_SEC))
+
+#define IS_RTC_PRESCALER(PRESCALER) ((PRESCALER) <= 0xFFFFF)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void RTC_ITConfig(u16 RTC_IT, FunctionalState NewState);
+void RTC_EnterConfigMode(void);
+void RTC_ExitConfigMode(void);
+u32 RTC_GetCounter(void);
+void RTC_SetCounter(u32 CounterValue);
+void RTC_SetPrescaler(u32 PrescalerValue);
+void RTC_SetAlarm(u32 AlarmValue);
+u32 RTC_GetDivider(void);
+void RTC_WaitForLastTask(void);
+void RTC_WaitForSynchro(void);
+FlagStatus RTC_GetFlagStatus(u16 RTC_FLAG);
+void RTC_ClearFlag(u16 RTC_FLAG);
+ITStatus RTC_GetITStatus(u16 RTC_IT);
+void RTC_ClearITPendingBit(u16 RTC_IT);
+
+#endif /* __STM32F10x_RTC_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_sdio.h b/src/stm32lib/inc/stm32f10x_sdio.h new file mode 100644 index 0000000..27f74f7 --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_sdio.h @@ -0,0 +1,337 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_sdio.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* SDIO firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_SDIO_H
+#define __STM32F10x_SDIO_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+typedef struct
+{
+ u8 SDIO_ClockDiv;
+ u32 SDIO_ClockEdge;
+ u32 SDIO_ClockBypass;
+ u32 SDIO_ClockPowerSave;
+ u32 SDIO_BusWide;
+ u32 SDIO_HardwareFlowControl;
+} SDIO_InitTypeDef;
+
+typedef struct
+{
+ u32 SDIO_Argument;
+ u32 SDIO_CmdIndex;
+ u32 SDIO_Response;
+ u32 SDIO_Wait;
+ u32 SDIO_CPSM;
+} SDIO_CmdInitTypeDef;
+
+typedef struct
+{
+ u32 SDIO_DataTimeOut;
+ u32 SDIO_DataLength;
+ u32 SDIO_DataBlockSize;
+ u32 SDIO_TransferDir;
+ u32 SDIO_TransferMode;
+ u32 SDIO_DPSM;
+} SDIO_DataInitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+/* SDIO Clock Edge -----------------------------------------------------------*/
+#define SDIO_ClockEdge_Rising ((u32)0x00000000)
+#define SDIO_ClockEdge_Falling ((u32)0x00002000)
+
+#define IS_SDIO_CLOCK_EDGE(EDGE) (((EDGE) == SDIO_ClockEdge_Rising) || \
+ ((EDGE) == SDIO_ClockEdge_Falling))
+/* SDIO Clock Bypass ----------------------------------------------------------*/
+#define SDIO_ClockBypass_Disable ((u32)0x00000000)
+#define SDIO_ClockBypass_Enable ((u32)0x00000400)
+
+#define IS_SDIO_CLOCK_BYPASS(BYPASS) (((BYPASS) == SDIO_ClockBypass_Disable) || \
+ ((BYPASS) == SDIO_ClockBypass_Enable))
+
+/* SDIO Clock Power Save ----------------------------------------------------*/
+#define SDIO_ClockPowerSave_Disable ((u32)0x00000000)
+#define SDIO_ClockPowerSave_Enable ((u32)0x00000200)
+
+#define IS_SDIO_CLOCK_POWER_SAVE(SAVE) (((SAVE) == SDIO_ClockPowerSave_Disable) || \
+ ((SAVE) == SDIO_ClockPowerSave_Enable))
+
+/* SDIO Bus Wide -------------------------------------------------------------*/
+#define SDIO_BusWide_1b ((u32)0x00000000)
+#define SDIO_BusWide_4b ((u32)0x00000800)
+#define SDIO_BusWide_8b ((u32)0x00001000)
+
+#define IS_SDIO_BUS_WIDE(WIDE) (((WIDE) == SDIO_BusWide_1b) || ((WIDE) == SDIO_BusWide_4b) || \
+ ((WIDE) == SDIO_BusWide_8b))
+
+/* SDIO Hardware Flow Control -----------------------------------------------*/
+#define SDIO_HardwareFlowControl_Disable ((u32)0x00000000)
+#define SDIO_HardwareFlowControl_Enable ((u32)0x00004000)
+
+#define IS_SDIO_HARDWARE_FLOW_CONTROL(CONTROL) (((CONTROL) == SDIO_HardwareFlowControl_Disable) || \
+ ((CONTROL) == SDIO_HardwareFlowControl_Enable))
+
+/* SDIO Power State ----------------------------------------------------------*/
+#define SDIO_PowerState_OFF ((u32)0x00000000)
+#define SDIO_PowerState_ON ((u32)0x00000003)
+
+#define IS_SDIO_POWER_STATE(STATE) (((STATE) == SDIO_PowerState_OFF) || ((STATE) == SDIO_PowerState_ON))
+
+/* SDIO Interrupt soucres ----------------------------------------------------*/
+#define SDIO_IT_CCRCFAIL ((u32)0x00000001)
+#define SDIO_IT_DCRCFAIL ((u32)0x00000002)
+#define SDIO_IT_CTIMEOUT ((u32)0x00000004)
+#define SDIO_IT_DTIMEOUT ((u32)0x00000008)
+#define SDIO_IT_TXUNDERR ((u32)0x00000010)
+#define SDIO_IT_RXOVERR ((u32)0x00000020)
+#define SDIO_IT_CMDREND ((u32)0x00000040)
+#define SDIO_IT_CMDSENT ((u32)0x00000080)
+#define SDIO_IT_DATAEND ((u32)0x00000100)
+#define SDIO_IT_STBITERR ((u32)0x00000200)
+#define SDIO_IT_DBCKEND ((u32)0x00000400)
+#define SDIO_IT_CMDACT ((u32)0x00000800)
+#define SDIO_IT_TXACT ((u32)0x00001000)
+#define SDIO_IT_RXACT ((u32)0x00002000)
+#define SDIO_IT_TXFIFOHE ((u32)0x00004000)
+#define SDIO_IT_RXFIFOHF ((u32)0x00008000)
+#define SDIO_IT_TXFIFOF ((u32)0x00010000)
+#define SDIO_IT_RXFIFOF ((u32)0x00020000)
+#define SDIO_IT_TXFIFOE ((u32)0x00040000)
+#define SDIO_IT_RXFIFOE ((u32)0x00080000)
+#define SDIO_IT_TXDAVL ((u32)0x00100000)
+#define SDIO_IT_RXDAVL ((u32)0x00200000)
+#define SDIO_IT_SDIOIT ((u32)0x00400000)
+#define SDIO_IT_CEATAEND ((u32)0x00800000)
+
+#define IS_SDIO_IT(IT) ((((IT) & (u32)0xFF000000) == 0x00) && ((IT) != (u32)0x00))
+
+/* SDIO Command Index -------------------------------------------------------*/
+#define IS_SDIO_CMD_INDEX(INDEX) ((INDEX) < 0x40)
+
+/* SDIO Response Type --------------------------------------------------------*/
+#define SDIO_Response_No ((u32)0x00000000)
+#define SDIO_Response_Short ((u32)0x00000040)
+#define SDIO_Response_Long ((u32)0x000000C0)
+
+#define IS_SDIO_RESPONSE(RESPONSE) (((RESPONSE) == SDIO_Response_No) || \
+ ((RESPONSE) == SDIO_Response_Short) || \
+ ((RESPONSE) == SDIO_Response_Long))
+
+/* SDIO Wait Interrupt State -------------------------------------------------*/
+#define SDIO_Wait_No ((u32)0x00000000) /* SDIO No Wait, TimeOut is enabled */
+#define SDIO_Wait_IT ((u32)0x00000100) /* SDIO Wait Interrupt Request */
+#define SDIO_Wait_Pend ((u32)0x00000200) /* SDIO Wait End of transfer */
+
+#define IS_SDIO_WAIT(WAIT) (((WAIT) == SDIO_Wait_No) || ((WAIT) == SDIO_Wait_IT) || \
+ ((WAIT) == SDIO_Wait_Pend))
+
+/* SDIO CPSM State -----------------------------------------------------------*/
+#define SDIO_CPSM_Disable ((u32)0x00000000)
+#define SDIO_CPSM_Enable ((u32)0x00000400)
+
+#define IS_SDIO_CPSM(CPSM) (((CPSM) == SDIO_CPSM_Enable) || ((CPSM) == SDIO_CPSM_Disable))
+
+/* SDIO Response Registers ---------------------------------------------------*/
+#define SDIO_RESP1 ((u32)0x00000000)
+#define SDIO_RESP2 ((u32)0x00000004)
+#define SDIO_RESP3 ((u32)0x00000008)
+#define SDIO_RESP4 ((u32)0x0000000C)
+
+#define IS_SDIO_RESP(RESP) (((RESP) == SDIO_RESP1) || ((RESP) == SDIO_RESP2) || \
+ ((RESP) == SDIO_RESP3) || ((RESP) == SDIO_RESP4))
+
+/* SDIO Data Length ----------------------------------------------------------*/
+#define IS_SDIO_DATA_LENGTH(LENGTH) ((LENGTH) <= 0x01FFFFFF)
+
+/* SDIO Data Block Size ------------------------------------------------------*/
+#define SDIO_DataBlockSize_1b ((u32)0x00000000)
+#define SDIO_DataBlockSize_2b ((u32)0x00000010)
+#define SDIO_DataBlockSize_4b ((u32)0x00000020)
+#define SDIO_DataBlockSize_8b ((u32)0x00000030)
+#define SDIO_DataBlockSize_16b ((u32)0x00000040)
+#define SDIO_DataBlockSize_32b ((u32)0x00000050)
+#define SDIO_DataBlockSize_64b ((u32)0x00000060)
+#define SDIO_DataBlockSize_128b ((u32)0x00000070)
+#define SDIO_DataBlockSize_256b ((u32)0x00000080)
+#define SDIO_DataBlockSize_512b ((u32)0x00000090)
+#define SDIO_DataBlockSize_1024b ((u32)0x000000A0)
+#define SDIO_DataBlockSize_2048b ((u32)0x000000B0)
+#define SDIO_DataBlockSize_4096b ((u32)0x000000C0)
+#define SDIO_DataBlockSize_8192b ((u32)0x000000D0)
+#define SDIO_DataBlockSize_16384b ((u32)0x000000E0)
+
+#define IS_SDIO_BLOCK_SIZE(SIZE) (((SIZE) == SDIO_DataBlockSize_1b) || \
+ ((SIZE) == SDIO_DataBlockSize_2b) || \
+ ((SIZE) == SDIO_DataBlockSize_4b) || \
+ ((SIZE) == SDIO_DataBlockSize_8b) || \
+ ((SIZE) == SDIO_DataBlockSize_16b) || \
+ ((SIZE) == SDIO_DataBlockSize_32b) || \
+ ((SIZE) == SDIO_DataBlockSize_64b) || \
+ ((SIZE) == SDIO_DataBlockSize_128b) || \
+ ((SIZE) == SDIO_DataBlockSize_256b) || \
+ ((SIZE) == SDIO_DataBlockSize_512b) || \
+ ((SIZE) == SDIO_DataBlockSize_1024b) || \
+ ((SIZE) == SDIO_DataBlockSize_2048b) || \
+ ((SIZE) == SDIO_DataBlockSize_4096b) || \
+ ((SIZE) == SDIO_DataBlockSize_8192b) || \
+ ((SIZE) == SDIO_DataBlockSize_16384b))
+
+/* SDIO Transfer Direction ---------------------------------------------------*/
+#define SDIO_TransferDir_ToCard ((u32)0x00000000)
+#define SDIO_TransferDir_ToSDIO ((u32)0x00000002)
+
+#define IS_SDIO_TRANSFER_DIR(DIR) (((DIR) == SDIO_TransferDir_ToCard) || \
+ ((DIR) == SDIO_TransferDir_ToSDIO))
+
+/* SDIO Transfer Type --------------------------------------------------------*/
+#define SDIO_TransferMode_Block ((u32)0x00000000)
+#define SDIO_TransferMode_Stream ((u32)0x00000004)
+
+#define IS_SDIO_TRANSFER_MODE(MODE) (((MODE) == SDIO_TransferMode_Stream) || \
+ ((MODE) == SDIO_TransferMode_Block))
+
+/* SDIO DPSM State -----------------------------------------------------------*/
+#define SDIO_DPSM_Disable ((u32)0x00000000)
+#define SDIO_DPSM_Enable ((u32)0x00000001)
+
+#define IS_SDIO_DPSM(DPSM) (((DPSM) == SDIO_DPSM_Enable) || ((DPSM) == SDIO_DPSM_Disable))
+
+/* SDIO Flags ----------------------------------------------------------------*/
+#define SDIO_FLAG_CCRCFAIL ((u32)0x00000001)
+#define SDIO_FLAG_DCRCFAIL ((u32)0x00000002)
+#define SDIO_FLAG_CTIMEOUT ((u32)0x00000004)
+#define SDIO_FLAG_DTIMEOUT ((u32)0x00000008)
+#define SDIO_FLAG_TXUNDERR ((u32)0x00000010)
+#define SDIO_FLAG_RXOVERR ((u32)0x00000020)
+#define SDIO_FLAG_CMDREND ((u32)0x00000040)
+#define SDIO_FLAG_CMDSENT ((u32)0x00000080)
+#define SDIO_FLAG_DATAEND ((u32)0x00000100)
+#define SDIO_FLAG_STBITERR ((u32)0x00000200)
+#define SDIO_FLAG_DBCKEND ((u32)0x00000400)
+#define SDIO_FLAG_CMDACT ((u32)0x00000800)
+#define SDIO_FLAG_TXACT ((u32)0x00001000)
+#define SDIO_FLAG_RXACT ((u32)0x00002000)
+#define SDIO_FLAG_TXFIFOHE ((u32)0x00004000)
+#define SDIO_FLAG_RXFIFOHF ((u32)0x00008000)
+#define SDIO_FLAG_TXFIFOF ((u32)0x00010000)
+#define SDIO_FLAG_RXFIFOF ((u32)0x00020000)
+#define SDIO_FLAG_TXFIFOE ((u32)0x00040000)
+#define SDIO_FLAG_RXFIFOE ((u32)0x00080000)
+#define SDIO_FLAG_TXDAVL ((u32)0x00100000)
+#define SDIO_FLAG_RXDAVL ((u32)0x00200000)
+#define SDIO_FLAG_SDIOIT ((u32)0x00400000)
+#define SDIO_FLAG_CEATAEND ((u32)0x00800000)
+
+#define IS_SDIO_FLAG(FLAG) (((FLAG) == SDIO_FLAG_CCRCFAIL) || \
+ ((FLAG) == SDIO_FLAG_DCRCFAIL) || \
+ ((FLAG) == SDIO_FLAG_CTIMEOUT) || \
+ ((FLAG) == SDIO_FLAG_DTIMEOUT) || \
+ ((FLAG) == SDIO_FLAG_TXUNDERR) || \
+ ((FLAG) == SDIO_FLAG_RXOVERR) || \
+ ((FLAG) == SDIO_FLAG_CMDREND) || \
+ ((FLAG) == SDIO_FLAG_CMDSENT) || \
+ ((FLAG) == SDIO_FLAG_DATAEND) || \
+ ((FLAG) == SDIO_FLAG_STBITERR) || \
+ ((FLAG) == SDIO_FLAG_DBCKEND) || \
+ ((FLAG) == SDIO_FLAG_CMDACT) || \
+ ((FLAG) == SDIO_FLAG_TXACT) || \
+ ((FLAG) == SDIO_FLAG_RXACT) || \
+ ((FLAG) == SDIO_FLAG_TXFIFOHE) || \
+ ((FLAG) == SDIO_FLAG_RXFIFOHF) || \
+ ((FLAG) == SDIO_FLAG_TXFIFOF) || \
+ ((FLAG) == SDIO_FLAG_RXFIFOF) || \
+ ((FLAG) == SDIO_FLAG_TXFIFOE) || \
+ ((FLAG) == SDIO_FLAG_RXFIFOE) || \
+ ((FLAG) == SDIO_FLAG_TXDAVL) || \
+ ((FLAG) == SDIO_FLAG_RXDAVL) || \
+ ((FLAG) == SDIO_FLAG_SDIOIT) || \
+ ((FLAG) == SDIO_FLAG_CEATAEND))
+
+#define IS_SDIO_CLEAR_FLAG(FLAG) ((((FLAG) & (u32)0xFF3FF800) == 0x00) && ((FLAG) != (u32)0x00))
+
+#define IS_SDIO_GET_IT(IT) (((IT) == SDIO_IT_CCRCFAIL) || \
+ ((IT) == SDIO_IT_DCRCFAIL) || \
+ ((IT) == SDIO_IT_CTIMEOUT) || \
+ ((IT) == SDIO_IT_DTIMEOUT) || \
+ ((IT) == SDIO_IT_TXUNDERR) || \
+ ((IT) == SDIO_IT_RXOVERR) || \
+ ((IT) == SDIO_IT_CMDREND) || \
+ ((IT) == SDIO_IT_CMDSENT) || \
+ ((IT) == SDIO_IT_DATAEND) || \
+ ((IT) == SDIO_IT_STBITERR) || \
+ ((IT) == SDIO_IT_DBCKEND) || \
+ ((IT) == SDIO_IT_CMDACT) || \
+ ((IT) == SDIO_IT_TXACT) || \
+ ((IT) == SDIO_IT_RXACT) || \
+ ((IT) == SDIO_IT_TXFIFOHE) || \
+ ((IT) == SDIO_IT_RXFIFOHF) || \
+ ((IT) == SDIO_IT_TXFIFOF) || \
+ ((IT) == SDIO_IT_RXFIFOF) || \
+ ((IT) == SDIO_IT_TXFIFOE) || \
+ ((IT) == SDIO_IT_RXFIFOE) || \
+ ((IT) == SDIO_IT_TXDAVL) || \
+ ((IT) == SDIO_IT_RXDAVL) || \
+ ((IT) == SDIO_IT_SDIOIT) || \
+ ((IT) == SDIO_IT_CEATAEND))
+
+#define IS_SDIO_CLEAR_IT(IT) ((((IT) & (u32)0xFF3FF800) == 0x00) && ((IT) != (u32)0x00))
+
+/* SDIO Read Wait Mode -------------------------------------------------------*/
+#define SDIO_ReadWaitMode_CLK ((u32)0x00000000)
+#define SDIO_ReadWaitMode_DATA2 ((u32)0x00000001)
+
+#define IS_SDIO_READWAIT_MODE(MODE) (((MODE) == SDIO_ReadWaitMode_CLK) || \
+ ((MODE) == SDIO_ReadWaitMode_DATA2))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void SDIO_DeInit(void);
+void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct);
+void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct);
+void SDIO_ClockCmd(FunctionalState NewState);
+void SDIO_SetPowerState(u32 SDIO_PowerState);
+u32 SDIO_GetPowerState(void);
+void SDIO_ITConfig(u32 SDIO_IT, FunctionalState NewState);
+void SDIO_DMACmd(FunctionalState NewState);
+void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct);
+void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct);
+u8 SDIO_GetCommandResponse(void);
+u32 SDIO_GetResponse(u32 SDIO_RESP);
+void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct);
+void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct);
+u32 SDIO_GetDataCounter(void);
+u32 SDIO_ReadData(void);
+void SDIO_WriteData(u32 Data);
+u32 SDIO_GetFIFOCount(void);
+void SDIO_StartSDIOReadWait(FunctionalState NewState);
+void SDIO_StopSDIOReadWait(FunctionalState NewState);
+void SDIO_SetSDIOReadWaitMode(u32 SDIO_ReadWaitMode);
+void SDIO_SetSDIOOperation(FunctionalState NewState);
+void SDIO_SendSDIOSuspendCmd(FunctionalState NewState);
+void SDIO_CommandCompletionCmd(FunctionalState NewState);
+void SDIO_CEATAITCmd(FunctionalState NewState);
+void SDIO_SendCEATACmd(FunctionalState NewState);
+FlagStatus SDIO_GetFlagStatus(u32 SDIO_FLAG);
+void SDIO_ClearFlag(u32 SDIO_FLAG);
+ITStatus SDIO_GetITStatus(u32 SDIO_IT);
+void SDIO_ClearITPendingBit(u32 SDIO_IT);
+
+#endif /* __STM32F10x_SDIO_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_spi.h b/src/stm32lib/inc/stm32f10x_spi.h new file mode 100644 index 0000000..b39817c --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_spi.h @@ -0,0 +1,289 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_spi.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* SPI firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_SPI_H
+#define __STM32F10x_SPI_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* SPI Init structure definition */
+typedef struct
+{
+ u16 SPI_Direction;
+ u16 SPI_Mode;
+ u16 SPI_DataSize;
+ u16 SPI_CPOL;
+ u16 SPI_CPHA;
+ u16 SPI_NSS;
+ u16 SPI_BaudRatePrescaler;
+ u16 SPI_FirstBit;
+ u16 SPI_CRCPolynomial;
+}SPI_InitTypeDef;
+
+/* I2S Init structure definition */
+typedef struct
+{
+ u16 I2S_Mode;
+ u16 I2S_Standard;
+ u16 I2S_DataFormat;
+ u16 I2S_MCLKOutput;
+ u16 I2S_AudioFreq;
+ u16 I2S_CPOL;
+}I2S_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+#define IS_SPI_ALL_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == SPI1_BASE) || \
+ ((*(u32*)&(PERIPH)) == SPI2_BASE) || \
+ ((*(u32*)&(PERIPH)) == SPI3_BASE))
+
+#define IS_SPI_23_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == SPI2_BASE) || \
+ ((*(u32*)&(PERIPH)) == SPI3_BASE))
+
+/* SPI data direction mode */
+#define SPI_Direction_2Lines_FullDuplex ((u16)0x0000)
+#define SPI_Direction_2Lines_RxOnly ((u16)0x0400)
+#define SPI_Direction_1Line_Rx ((u16)0x8000)
+#define SPI_Direction_1Line_Tx ((u16)0xC000)
+
+#define IS_SPI_DIRECTION_MODE(MODE) (((MODE) == SPI_Direction_2Lines_FullDuplex) || \
+ ((MODE) == SPI_Direction_2Lines_RxOnly) || \
+ ((MODE) == SPI_Direction_1Line_Rx) || \
+ ((MODE) == SPI_Direction_1Line_Tx))
+
+/* SPI master/slave mode */
+#define SPI_Mode_Master ((u16)0x0104)
+#define SPI_Mode_Slave ((u16)0x0000)
+
+#define IS_SPI_MODE(MODE) (((MODE) == SPI_Mode_Master) || \
+ ((MODE) == SPI_Mode_Slave))
+
+/* SPI data size */
+#define SPI_DataSize_16b ((u16)0x0800)
+#define SPI_DataSize_8b ((u16)0x0000)
+
+#define IS_SPI_DATASIZE(DATASIZE) (((DATASIZE) == SPI_DataSize_16b) || \
+ ((DATASIZE) == SPI_DataSize_8b))
+
+/* SPI Clock Polarity */
+#define SPI_CPOL_Low ((u16)0x0000)
+#define SPI_CPOL_High ((u16)0x0002)
+
+#define IS_SPI_CPOL(CPOL) (((CPOL) == SPI_CPOL_Low) || \
+ ((CPOL) == SPI_CPOL_High))
+
+/* SPI Clock Phase */
+#define SPI_CPHA_1Edge ((u16)0x0000)
+#define SPI_CPHA_2Edge ((u16)0x0001)
+
+#define IS_SPI_CPHA(CPHA) (((CPHA) == SPI_CPHA_1Edge) || \
+ ((CPHA) == SPI_CPHA_2Edge))
+
+/* SPI Slave Select management */
+#define SPI_NSS_Soft ((u16)0x0200)
+#define SPI_NSS_Hard ((u16)0x0000)
+
+#define IS_SPI_NSS(NSS) (((NSS) == SPI_NSS_Soft) || \
+ ((NSS) == SPI_NSS_Hard))
+
+/* SPI BaudRate Prescaler */
+#define SPI_BaudRatePrescaler_2 ((u16)0x0000)
+#define SPI_BaudRatePrescaler_4 ((u16)0x0008)
+#define SPI_BaudRatePrescaler_8 ((u16)0x0010)
+#define SPI_BaudRatePrescaler_16 ((u16)0x0018)
+#define SPI_BaudRatePrescaler_32 ((u16)0x0020)
+#define SPI_BaudRatePrescaler_64 ((u16)0x0028)
+#define SPI_BaudRatePrescaler_128 ((u16)0x0030)
+#define SPI_BaudRatePrescaler_256 ((u16)0x0038)
+
+#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER) (((PRESCALER) == SPI_BaudRatePrescaler_2) || \
+ ((PRESCALER) == SPI_BaudRatePrescaler_4) || \
+ ((PRESCALER) == SPI_BaudRatePrescaler_8) || \
+ ((PRESCALER) == SPI_BaudRatePrescaler_16) || \
+ ((PRESCALER) == SPI_BaudRatePrescaler_32) || \
+ ((PRESCALER) == SPI_BaudRatePrescaler_64) || \
+ ((PRESCALER) == SPI_BaudRatePrescaler_128) || \
+ ((PRESCALER) == SPI_BaudRatePrescaler_256))
+
+/* SPI MSB/LSB transmission */
+#define SPI_FirstBit_MSB ((u16)0x0000)
+#define SPI_FirstBit_LSB ((u16)0x0080)
+
+#define IS_SPI_FIRST_BIT(BIT) (((BIT) == SPI_FirstBit_MSB) || \
+ ((BIT) == SPI_FirstBit_LSB))
+
+/* I2S Mode */
+#define I2S_Mode_SlaveTx ((u16)0x0000)
+#define I2S_Mode_SlaveRx ((u16)0x0100)
+#define I2S_Mode_MasterTx ((u16)0x0200)
+#define I2S_Mode_MasterRx ((u16)0x0300)
+
+#define IS_I2S_MODE(MODE) (((MODE) == I2S_Mode_SlaveTx) || \
+ ((MODE) == I2S_Mode_SlaveRx) || \
+ ((MODE) == I2S_Mode_MasterTx) || \
+ ((MODE) == I2S_Mode_MasterRx) )
+
+/* I2S Standard */
+#define I2S_Standard_Phillips ((u16)0x0000)
+#define I2S_Standard_MSB ((u16)0x0010)
+#define I2S_Standard_LSB ((u16)0x0020)
+#define I2S_Standard_PCMShort ((u16)0x0030)
+#define I2S_Standard_PCMLong ((u16)0x00B0)
+
+#define IS_I2S_STANDARD(STANDARD) (((STANDARD) == I2S_Standard_Phillips) || \
+ ((STANDARD) == I2S_Standard_MSB) || \
+ ((STANDARD) == I2S_Standard_LSB) || \
+ ((STANDARD) == I2S_Standard_PCMShort) || \
+ ((STANDARD) == I2S_Standard_PCMLong))
+
+/* I2S Data Format */
+#define I2S_DataFormat_16b ((u16)0x0000)
+#define I2S_DataFormat_16bextended ((u16)0x0001)
+#define I2S_DataFormat_24b ((u16)0x0003)
+#define I2S_DataFormat_32b ((u16)0x0005)
+
+#define IS_I2S_DATA_FORMAT(FORMAT) (((FORMAT) == I2S_DataFormat_16b) || \
+ ((FORMAT) == I2S_DataFormat_16bextended) || \
+ ((FORMAT) == I2S_DataFormat_24b) || \
+ ((FORMAT) == I2S_DataFormat_32b))
+
+/* I2S MCLK Output */
+#define I2S_MCLKOutput_Enable ((u16)0x0200)
+#define I2S_MCLKOutput_Disable ((u16)0x0000)
+
+#define IS_I2S_MCLK_OUTPUT(OUTPUT) (((OUTPUT) == I2S_MCLKOutput_Enable) || \
+ ((OUTPUT) == I2S_MCLKOutput_Disable))
+
+/* I2S Audio Frequency */
+#define I2S_AudioFreq_48k ((u16)48000)
+#define I2S_AudioFreq_44k ((u16)44100)
+#define I2S_AudioFreq_22k ((u16)22050)
+#define I2S_AudioFreq_16k ((u16)16000)
+#define I2S_AudioFreq_8k ((u16)8000)
+#define I2S_AudioFreq_Default ((u16)2)
+
+#define IS_I2S_AUDIO_FREQ(FREQ) (((FREQ) == I2S_AudioFreq_48k) || \
+ ((FREQ) == I2S_AudioFreq_44k) || \
+ ((FREQ) == I2S_AudioFreq_22k) || \
+ ((FREQ) == I2S_AudioFreq_16k) || \
+ ((FREQ) == I2S_AudioFreq_8k) || \
+ ((FREQ) == I2S_AudioFreq_Default))
+
+/* I2S Clock Polarity */
+#define I2S_CPOL_Low ((u16)0x0000)
+#define I2S_CPOL_High ((u16)0x0008)
+
+#define IS_I2S_CPOL(CPOL) (((CPOL) == I2S_CPOL_Low) || \
+ ((CPOL) == I2S_CPOL_High))
+
+/* SPI_I2S DMA transfer requests */
+#define SPI_I2S_DMAReq_Tx ((u16)0x0002)
+#define SPI_I2S_DMAReq_Rx ((u16)0x0001)
+
+#define IS_SPI_I2S_DMAREQ(DMAREQ) ((((DMAREQ) & (u16)0xFFFC) == 0x00) && ((DMAREQ) != 0x00))
+
+/* SPI NSS internal software mangement */
+#define SPI_NSSInternalSoft_Set ((u16)0x0100)
+#define SPI_NSSInternalSoft_Reset ((u16)0xFEFF)
+
+#define IS_SPI_NSS_INTERNAL(INTERNAL) (((INTERNAL) == SPI_NSSInternalSoft_Set) || \
+ ((INTERNAL) == SPI_NSSInternalSoft_Reset))
+
+/* SPI CRC Transmit/Receive */
+#define SPI_CRC_Tx ((u8)0x00)
+#define SPI_CRC_Rx ((u8)0x01)
+
+#define IS_SPI_CRC(CRC) (((CRC) == SPI_CRC_Tx) || ((CRC) == SPI_CRC_Rx))
+
+/* SPI direction transmit/receive */
+#define SPI_Direction_Rx ((u16)0xBFFF)
+#define SPI_Direction_Tx ((u16)0x4000)
+
+#define IS_SPI_DIRECTION(DIRECTION) (((DIRECTION) == SPI_Direction_Rx) || \
+ ((DIRECTION) == SPI_Direction_Tx))
+
+/* SPI_I2S interrupts definition */
+#define SPI_I2S_IT_TXE ((u8)0x71)
+#define SPI_I2S_IT_RXNE ((u8)0x60)
+#define SPI_I2S_IT_ERR ((u8)0x50)
+
+#define IS_SPI_I2S_CONFIG_IT(IT) (((IT) == SPI_I2S_IT_TXE) || \
+ ((IT) == SPI_I2S_IT_RXNE) || \
+ ((IT) == SPI_I2S_IT_ERR))
+
+#define SPI_I2S_IT_OVR ((u8)0x56)
+#define SPI_IT_MODF ((u8)0x55)
+#define SPI_IT_CRCERR ((u8)0x54)
+#define I2S_IT_UDR ((u8)0x53)
+
+#define IS_SPI_I2S_CLEAR_IT(IT) (((IT) == SPI_IT_CRCERR))
+
+#define IS_SPI_I2S_GET_IT(IT) (((IT) == SPI_I2S_IT_RXNE) || ((IT) == SPI_I2S_IT_TXE) || \
+ ((IT) == I2S_IT_UDR) || ((IT) == SPI_IT_CRCERR) || \
+ ((IT) == SPI_IT_MODF) || ((IT) == SPI_I2S_IT_OVR))
+
+/* SPI_I2S flags definition */
+#define SPI_I2S_FLAG_RXNE ((u16)0x0001)
+#define SPI_I2S_FLAG_TXE ((u16)0x0002)
+#define I2S_FLAG_CHSIDE ((u16)0x0004)
+#define I2S_FLAG_UDR ((u16)0x0008)
+#define SPI_FLAG_CRCERR ((u16)0x0010)
+#define SPI_FLAG_MODF ((u16)0x0020)
+#define SPI_I2S_FLAG_OVR ((u16)0x0040)
+#define SPI_I2S_FLAG_BSY ((u16)0x0080)
+
+#define IS_SPI_I2S_CLEAR_FLAG(FLAG) (((FLAG) == SPI_FLAG_CRCERR))
+
+#define IS_SPI_I2S_GET_FLAG(FLAG) (((FLAG) == SPI_I2S_FLAG_BSY) || ((FLAG) == SPI_I2S_FLAG_OVR) || \
+ ((FLAG) == SPI_FLAG_MODF) || ((FLAG) == SPI_FLAG_CRCERR) || \
+ ((FLAG) == I2S_FLAG_UDR) || ((FLAG) == I2S_FLAG_CHSIDE) || \
+ ((FLAG) == SPI_I2S_FLAG_TXE) || ((FLAG) == SPI_I2S_FLAG_RXNE))
+
+/* SPI CRC polynomial --------------------------------------------------------*/
+#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL) ((POLYNOMIAL) >= 0x1)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void SPI_I2S_DeInit(SPI_TypeDef* SPIx);
+void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct);
+void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct);
+void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct);
+void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct);
+void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState);
+void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState);
+void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, u8 SPI_I2S_IT, FunctionalState NewState);
+void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, u16 SPI_I2S_DMAReq, FunctionalState NewState);
+void SPI_I2S_SendData(SPI_TypeDef* SPIx, u16 Data);
+u16 SPI_I2S_ReceiveData(SPI_TypeDef* SPIx);
+void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, u16 SPI_NSSInternalSoft);
+void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState);
+void SPI_DataSizeConfig(SPI_TypeDef* SPIx, u16 SPI_DataSize);
+void SPI_TransmitCRC(SPI_TypeDef* SPIx);
+void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState);
+u16 SPI_GetCRC(SPI_TypeDef* SPIx, u8 SPI_CRC);
+u16 SPI_GetCRCPolynomial(SPI_TypeDef* SPIx);
+void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, u16 SPI_Direction);
+FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, u16 SPI_I2S_FLAG);
+void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, u16 SPI_I2S_FLAG);
+ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, u8 SPI_I2S_IT);
+void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, u8 SPI_I2S_IT);
+
+#endif /*__STM32F10x_SPI_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_systick.h b/src/stm32lib/inc/stm32f10x_systick.h new file mode 100644 index 0000000..3dfb036 --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_systick.h @@ -0,0 +1,70 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_systick.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* SysTick firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_SYSTICK_H
+#define __STM32F10x_SYSTICK_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* SysTick clock source */
+#define SysTick_CLKSource_HCLK_Div8 ((u32)0xFFFFFFFB)
+#define SysTick_CLKSource_HCLK ((u32)0x00000004)
+
+#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \
+ ((SOURCE) == SysTick_CLKSource_HCLK_Div8))
+
+/* SysTick counter state */
+#define SysTick_Counter_Disable ((u32)0xFFFFFFFE)
+#define SysTick_Counter_Enable ((u32)0x00000001)
+#define SysTick_Counter_Clear ((u32)0x00000000)
+
+#define IS_SYSTICK_COUNTER(COUNTER) (((COUNTER) == SysTick_Counter_Disable) || \
+ ((COUNTER) == SysTick_Counter_Enable) || \
+ ((COUNTER) == SysTick_Counter_Clear))
+
+/* SysTick Flag */
+#define SysTick_FLAG_COUNT ((u32)0x00000010)
+#define SysTick_FLAG_SKEW ((u32)0x0000001E)
+#define SysTick_FLAG_NOREF ((u32)0x0000001F)
+
+#define IS_SYSTICK_FLAG(FLAG) (((FLAG) == SysTick_FLAG_COUNT) || \
+ ((FLAG) == SysTick_FLAG_SKEW) || \
+ ((FLAG) == SysTick_FLAG_NOREF))
+
+#define IS_SYSTICK_RELOAD(RELOAD) (((RELOAD) > 0) && ((RELOAD) <= 0xFFFFFF))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+#ifdef __cplusplus
+extern "C" {
+#endif
+void SysTick_CLKSourceConfig(u32 SysTick_CLKSource);
+void SysTick_SetReload(u32 Reload);
+void SysTick_CounterCmd(u32 SysTick_Counter);
+void SysTick_ITConfig(FunctionalState NewState);
+u32 SysTick_GetCounter(void);
+FlagStatus SysTick_GetFlagStatus(u8 SysTick_FLAG);
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_SYSTICK_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_tim.h b/src/stm32lib/inc/stm32f10x_tim.h new file mode 100644 index 0000000..423516c --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_tim.h @@ -0,0 +1,784 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_tim.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* TIM firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_TIM_H
+#define __STM32F10x_TIM_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+
+/* TIM Time Base Init structure definition */
+typedef struct
+{
+ u16 TIM_Prescaler;
+ u16 TIM_CounterMode;
+ u16 TIM_Period;
+ u16 TIM_ClockDivision;
+ u8 TIM_RepetitionCounter;
+} TIM_TimeBaseInitTypeDef;
+
+/* TIM Output Compare Init structure definition */
+typedef struct
+{
+ u16 TIM_OCMode;
+ u16 TIM_OutputState;
+ u16 TIM_OutputNState;
+ u16 TIM_Pulse;
+ u16 TIM_OCPolarity;
+ u16 TIM_OCNPolarity;
+ u16 TIM_OCIdleState;
+ u16 TIM_OCNIdleState;
+} TIM_OCInitTypeDef;
+
+/* TIM Input Capture Init structure definition */
+typedef struct
+{
+ u16 TIM_Channel;
+ u16 TIM_ICPolarity;
+ u16 TIM_ICSelection;
+ u16 TIM_ICPrescaler;
+ u16 TIM_ICFilter;
+} TIM_ICInitTypeDef;
+
+/* BDTR structure definition */
+typedef struct
+{
+ u16 TIM_OSSRState;
+ u16 TIM_OSSIState;
+ u16 TIM_LOCKLevel;
+ u16 TIM_DeadTime;
+ u16 TIM_Break;
+ u16 TIM_BreakPolarity;
+ u16 TIM_AutomaticOutput;
+} TIM_BDTRInitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+#define IS_TIM_ALL_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == TIM1_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM2_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM3_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM4_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM5_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM6_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM7_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM8_BASE))
+
+#define IS_TIM_18_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == TIM1_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM8_BASE))
+
+#define IS_TIM_123458_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == TIM1_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM2_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM3_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM4_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM5_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM8_BASE))
+
+/* TIM Output Compare and PWM modes -----------------------------------------*/
+#define TIM_OCMode_Timing ((u16)0x0000)
+#define TIM_OCMode_Active ((u16)0x0010)
+#define TIM_OCMode_Inactive ((u16)0x0020)
+#define TIM_OCMode_Toggle ((u16)0x0030)
+#define TIM_OCMode_PWM1 ((u16)0x0060)
+#define TIM_OCMode_PWM2 ((u16)0x0070)
+
+#define IS_TIM_OC_MODE(MODE) (((MODE) == TIM_OCMode_Timing) || \
+ ((MODE) == TIM_OCMode_Active) || \
+ ((MODE) == TIM_OCMode_Inactive) || \
+ ((MODE) == TIM_OCMode_Toggle)|| \
+ ((MODE) == TIM_OCMode_PWM1) || \
+ ((MODE) == TIM_OCMode_PWM2))
+
+#define IS_TIM_OCM(MODE) (((MODE) == TIM_OCMode_Timing) || \
+ ((MODE) == TIM_OCMode_Active) || \
+ ((MODE) == TIM_OCMode_Inactive) || \
+ ((MODE) == TIM_OCMode_Toggle)|| \
+ ((MODE) == TIM_OCMode_PWM1) || \
+ ((MODE) == TIM_OCMode_PWM2) || \
+ ((MODE) == TIM_ForcedAction_Active) || \
+ ((MODE) == TIM_ForcedAction_InActive))
+/* TIM One Pulse Mode -------------------------------------------------------*/
+#define TIM_OPMode_Single ((u16)0x0008)
+#define TIM_OPMode_Repetitive ((u16)0x0000)
+
+#define IS_TIM_OPM_MODE(MODE) (((MODE) == TIM_OPMode_Single) || \
+ ((MODE) == TIM_OPMode_Repetitive))
+
+/* TIM Channel -------------------------------------------------------------*/
+#define TIM_Channel_1 ((u16)0x0000)
+#define TIM_Channel_2 ((u16)0x0004)
+#define TIM_Channel_3 ((u16)0x0008)
+#define TIM_Channel_4 ((u16)0x000C)
+
+#define IS_TIM_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
+ ((CHANNEL) == TIM_Channel_2) || \
+ ((CHANNEL) == TIM_Channel_3) || \
+ ((CHANNEL) == TIM_Channel_4))
+
+#define IS_TIM_PWMI_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
+ ((CHANNEL) == TIM_Channel_2))
+
+#define IS_TIM_COMPLEMENTARY_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
+ ((CHANNEL) == TIM_Channel_2) || \
+ ((CHANNEL) == TIM_Channel_3))
+/* TIM Clock Division CKD --------------------------------------------------*/
+#define TIM_CKD_DIV1 ((u16)0x0000)
+#define TIM_CKD_DIV2 ((u16)0x0100)
+#define TIM_CKD_DIV4 ((u16)0x0200)
+
+#define IS_TIM_CKD_DIV(DIV) (((DIV) == TIM_CKD_DIV1) || \
+ ((DIV) == TIM_CKD_DIV2) || \
+ ((DIV) == TIM_CKD_DIV4))
+
+/* TIM Counter Mode --------------------------------------------------------*/
+#define TIM_CounterMode_Up ((u16)0x0000)
+#define TIM_CounterMode_Down ((u16)0x0010)
+#define TIM_CounterMode_CenterAligned1 ((u16)0x0020)
+#define TIM_CounterMode_CenterAligned2 ((u16)0x0040)
+#define TIM_CounterMode_CenterAligned3 ((u16)0x0060)
+
+#define IS_TIM_COUNTER_MODE(MODE) (((MODE) == TIM_CounterMode_Up) || \
+ ((MODE) == TIM_CounterMode_Down) || \
+ ((MODE) == TIM_CounterMode_CenterAligned1) || \
+ ((MODE) == TIM_CounterMode_CenterAligned2) || \
+ ((MODE) == TIM_CounterMode_CenterAligned3))
+
+/* TIM Output Compare Polarity ---------------------------------------------*/
+#define TIM_OCPolarity_High ((u16)0x0000)
+#define TIM_OCPolarity_Low ((u16)0x0002)
+
+#define IS_TIM_OC_POLARITY(POLARITY) (((POLARITY) == TIM_OCPolarity_High) || \
+ ((POLARITY) == TIM_OCPolarity_Low))
+
+/* TIM Output Compare N Polarity -------------------------------------------*/
+#define TIM_OCNPolarity_High ((u16)0x0000)
+#define TIM_OCNPolarity_Low ((u16)0x0008)
+
+#define IS_TIM_OCN_POLARITY(POLARITY) (((POLARITY) == TIM_OCNPolarity_High) || \
+ ((POLARITY) == TIM_OCNPolarity_Low))
+
+/* TIM Output Compare states -----------------------------------------------*/
+#define TIM_OutputState_Disable ((u16)0x0000)
+#define TIM_OutputState_Enable ((u16)0x0001)
+
+#define IS_TIM_OUTPUT_STATE(STATE) (((STATE) == TIM_OutputState_Disable) || \
+ ((STATE) == TIM_OutputState_Enable))
+
+/* TIM Output Compare N States ---------------------------------------------*/
+#define TIM_OutputNState_Disable ((u16)0x0000)
+#define TIM_OutputNState_Enable ((u16)0x0004)
+
+#define IS_TIM_OUTPUTN_STATE(STATE) (((STATE) == TIM_OutputNState_Disable) || \
+ ((STATE) == TIM_OutputNState_Enable))
+
+/* TIM Capture Compare States -----------------------------------------------*/
+#define TIM_CCx_Enable ((u16)0x0001)
+#define TIM_CCx_Disable ((u16)0x0000)
+
+#define IS_TIM_CCX(CCX) (((CCX) == TIM_CCx_Enable) || \
+ ((CCX) == TIM_CCx_Disable))
+
+/* TIM Capture Compare N States --------------------------------------------*/
+#define TIM_CCxN_Enable ((u16)0x0004)
+#define TIM_CCxN_Disable ((u16)0x0000)
+
+#define IS_TIM_CCXN(CCXN) (((CCXN) == TIM_CCxN_Enable) || \
+ ((CCXN) == TIM_CCxN_Disable))
+
+/* Break Input enable/disable -----------------------------------------------*/
+#define TIM_Break_Enable ((u16)0x1000)
+#define TIM_Break_Disable ((u16)0x0000)
+
+#define IS_TIM_BREAK_STATE(STATE) (((STATE) == TIM_Break_Enable) || \
+ ((STATE) == TIM_Break_Disable))
+
+/* Break Polarity -----------------------------------------------------------*/
+#define TIM_BreakPolarity_Low ((u16)0x0000)
+#define TIM_BreakPolarity_High ((u16)0x2000)
+
+#define IS_TIM_BREAK_POLARITY(POLARITY) (((POLARITY) == TIM_BreakPolarity_Low) || \
+ ((POLARITY) == TIM_BreakPolarity_High))
+
+/* TIM AOE Bit Set/Reset ---------------------------------------------------*/
+#define TIM_AutomaticOutput_Enable ((u16)0x4000)
+#define TIM_AutomaticOutput_Disable ((u16)0x0000)
+
+#define IS_TIM_AUTOMATIC_OUTPUT_STATE(STATE) (((STATE) == TIM_AutomaticOutput_Enable) || \
+ ((STATE) == TIM_AutomaticOutput_Disable))
+/* Lock levels --------------------------------------------------------------*/
+#define TIM_LOCKLevel_OFF ((u16)0x0000)
+#define TIM_LOCKLevel_1 ((u16)0x0100)
+#define TIM_LOCKLevel_2 ((u16)0x0200)
+#define TIM_LOCKLevel_3 ((u16)0x0300)
+
+#define IS_TIM_LOCK_LEVEL(LEVEL) (((LEVEL) == TIM_LOCKLevel_OFF) || \
+ ((LEVEL) == TIM_LOCKLevel_1) || \
+ ((LEVEL) == TIM_LOCKLevel_2) || \
+ ((LEVEL) == TIM_LOCKLevel_3))
+
+/* OSSI: Off-State Selection for Idle mode states ---------------------------*/
+#define TIM_OSSIState_Enable ((u16)0x0400)
+#define TIM_OSSIState_Disable ((u16)0x0000)
+
+#define IS_TIM_OSSI_STATE(STATE) (((STATE) == TIM_OSSIState_Enable) || \
+ ((STATE) == TIM_OSSIState_Disable))
+
+/* OSSR: Off-State Selection for Run mode states ----------------------------*/
+#define TIM_OSSRState_Enable ((u16)0x0800)
+#define TIM_OSSRState_Disable ((u16)0x0000)
+
+#define IS_TIM_OSSR_STATE(STATE) (((STATE) == TIM_OSSRState_Enable) || \
+ ((STATE) == TIM_OSSRState_Disable))
+
+/* TIM Output Compare Idle State -------------------------------------------*/
+#define TIM_OCIdleState_Set ((u16)0x0100)
+#define TIM_OCIdleState_Reset ((u16)0x0000)
+
+#define IS_TIM_OCIDLE_STATE(STATE) (((STATE) == TIM_OCIdleState_Set) || \
+ ((STATE) == TIM_OCIdleState_Reset))
+
+/* TIM Output Compare N Idle State -----------------------------------------*/
+#define TIM_OCNIdleState_Set ((u16)0x0200)
+#define TIM_OCNIdleState_Reset ((u16)0x0000)
+
+#define IS_TIM_OCNIDLE_STATE(STATE) (((STATE) == TIM_OCNIdleState_Set) || \
+ ((STATE) == TIM_OCNIdleState_Reset))
+
+/* TIM Input Capture Polarity ----------------------------------------------*/
+#define TIM_ICPolarity_Rising ((u16)0x0000)
+#define TIM_ICPolarity_Falling ((u16)0x0002)
+
+#define IS_TIM_IC_POLARITY(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \
+ ((POLARITY) == TIM_ICPolarity_Falling))
+
+/* TIM Input Capture Selection ---------------------------------------------*/
+#define TIM_ICSelection_DirectTI ((u16)0x0001)
+#define TIM_ICSelection_IndirectTI ((u16)0x0002)
+#define TIM_ICSelection_TRC ((u16)0x0003)
+
+#define IS_TIM_IC_SELECTION(SELECTION) (((SELECTION) == TIM_ICSelection_DirectTI) || \
+ ((SELECTION) == TIM_ICSelection_IndirectTI) || \
+ ((SELECTION) == TIM_ICSelection_TRC))
+
+/* TIM Input Capture Prescaler ---------------------------------------------*/
+#define TIM_ICPSC_DIV1 ((u16)0x0000)
+#define TIM_ICPSC_DIV2 ((u16)0x0004)
+#define TIM_ICPSC_DIV4 ((u16)0x0008)
+#define TIM_ICPSC_DIV8 ((u16)0x000C)
+
+#define IS_TIM_IC_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ICPSC_DIV1) || \
+ ((PRESCALER) == TIM_ICPSC_DIV2) || \
+ ((PRESCALER) == TIM_ICPSC_DIV4) || \
+ ((PRESCALER) == TIM_ICPSC_DIV8))
+
+/* TIM interrupt sources ---------------------------------------------------*/
+#define TIM_IT_Update ((u16)0x0001)
+#define TIM_IT_CC1 ((u16)0x0002)
+#define TIM_IT_CC2 ((u16)0x0004)
+#define TIM_IT_CC3 ((u16)0x0008)
+#define TIM_IT_CC4 ((u16)0x0010)
+#define TIM_IT_COM ((u16)0x0020)
+#define TIM_IT_Trigger ((u16)0x0040)
+#define TIM_IT_Break ((u16)0x0080)
+
+#define IS_TIM_IT(IT) ((((IT) & (u16)0xFF00) == 0x0000) && ((IT) != 0x0000))
+
+#define IS_TIM_PERIPH_IT(PERIPH, TIM_IT) ((((((*(u32*)&(PERIPH)) == TIM2_BASE) || (((*(u32*)&(PERIPH)) == TIM3_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM4_BASE)) || (((*(u32*)&(PERIPH)) == TIM5_BASE))))&& \
+ (((TIM_IT) & (u16)0xFFA0) == 0x0000) && ((TIM_IT) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM1_BASE) || (((*(u32*)&(PERIPH)) == TIM8_BASE))))&& \
+ (((TIM_IT) & (u16)0xFF00) == 0x0000) && ((TIM_IT) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM6_BASE) || (((*(u32*)&(PERIPH)) == TIM7_BASE))))&& \
+ (((TIM_IT) & (u16)0xFFFE) == 0x0000) && ((TIM_IT) != 0x0000)))
+
+#define IS_TIM_GET_IT(IT) (((IT) == TIM_IT_Update) || \
+ ((IT) == TIM_IT_CC1) || \
+ ((IT) == TIM_IT_CC2) || \
+ ((IT) == TIM_IT_CC3) || \
+ ((IT) == TIM_IT_CC4) || \
+ ((IT) == TIM_IT_COM) || \
+ ((IT) == TIM_IT_Trigger) || \
+ ((IT) == TIM_IT_Break))
+
+/* TIM DMA Base address ----------------------------------------------------*/
+#define TIM_DMABase_CR1 ((u16)0x0000)
+#define TIM_DMABase_CR2 ((u16)0x0001)
+#define TIM_DMABase_SMCR ((u16)0x0002)
+#define TIM_DMABase_DIER ((u16)0x0003)
+#define TIM_DMABase_SR ((u16)0x0004)
+#define TIM_DMABase_EGR ((u16)0x0005)
+#define TIM_DMABase_CCMR1 ((u16)0x0006)
+#define TIM_DMABase_CCMR2 ((u16)0x0007)
+#define TIM_DMABase_CCER ((u16)0x0008)
+#define TIM_DMABase_CNT ((u16)0x0009)
+#define TIM_DMABase_PSC ((u16)0x000A)
+#define TIM_DMABase_ARR ((u16)0x000B)
+#define TIM_DMABase_RCR ((u16)0x000C)
+#define TIM_DMABase_CCR1 ((u16)0x000D)
+#define TIM_DMABase_CCR2 ((u16)0x000E)
+#define TIM_DMABase_CCR3 ((u16)0x000F)
+#define TIM_DMABase_CCR4 ((u16)0x0010)
+#define TIM_DMABase_BDTR ((u16)0x0011)
+#define TIM_DMABase_DCR ((u16)0x0012)
+
+#define IS_TIM_DMA_BASE(BASE) (((BASE) == TIM_DMABase_CR1) || \
+ ((BASE) == TIM_DMABase_CR2) || \
+ ((BASE) == TIM_DMABase_SMCR) || \
+ ((BASE) == TIM_DMABase_DIER) || \
+ ((BASE) == TIM_DMABase_SR) || \
+ ((BASE) == TIM_DMABase_EGR) || \
+ ((BASE) == TIM_DMABase_CCMR1) || \
+ ((BASE) == TIM_DMABase_CCMR2) || \
+ ((BASE) == TIM_DMABase_CCER) || \
+ ((BASE) == TIM_DMABase_CNT) || \
+ ((BASE) == TIM_DMABase_PSC) || \
+ ((BASE) == TIM_DMABase_ARR) || \
+ ((BASE) == TIM_DMABase_RCR) || \
+ ((BASE) == TIM_DMABase_CCR1) || \
+ ((BASE) == TIM_DMABase_CCR2) || \
+ ((BASE) == TIM_DMABase_CCR3) || \
+ ((BASE) == TIM_DMABase_CCR4) || \
+ ((BASE) == TIM_DMABase_BDTR) || \
+ ((BASE) == TIM_DMABase_DCR))
+
+/* TIM DMA Burst Length ----------------------------------------------------*/
+#define TIM_DMABurstLength_1Byte ((u16)0x0000)
+#define TIM_DMABurstLength_2Bytes ((u16)0x0100)
+#define TIM_DMABurstLength_3Bytes ((u16)0x0200)
+#define TIM_DMABurstLength_4Bytes ((u16)0x0300)
+#define TIM_DMABurstLength_5Bytes ((u16)0x0400)
+#define TIM_DMABurstLength_6Bytes ((u16)0x0500)
+#define TIM_DMABurstLength_7Bytes ((u16)0x0600)
+#define TIM_DMABurstLength_8Bytes ((u16)0x0700)
+#define TIM_DMABurstLength_9Bytes ((u16)0x0800)
+#define TIM_DMABurstLength_10Bytes ((u16)0x0900)
+#define TIM_DMABurstLength_11Bytes ((u16)0x0A00)
+#define TIM_DMABurstLength_12Bytes ((u16)0x0B00)
+#define TIM_DMABurstLength_13Bytes ((u16)0x0C00)
+#define TIM_DMABurstLength_14Bytes ((u16)0x0D00)
+#define TIM_DMABurstLength_15Bytes ((u16)0x0E00)
+#define TIM_DMABurstLength_16Bytes ((u16)0x0F00)
+#define TIM_DMABurstLength_17Bytes ((u16)0x1000)
+#define TIM_DMABurstLength_18Bytes ((u16)0x1100)
+
+#define IS_TIM_DMA_LENGTH(LENGTH) (((LENGTH) == TIM_DMABurstLength_1Byte) || \
+ ((LENGTH) == TIM_DMABurstLength_2Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_3Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_4Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_5Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_6Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_7Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_8Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_9Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_10Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_11Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_12Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_13Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_14Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_15Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_16Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_17Bytes) || \
+ ((LENGTH) == TIM_DMABurstLength_18Bytes))
+
+/* TIM DMA sources ---------------------------------------------------------*/
+#define TIM_DMA_Update ((u16)0x0100)
+#define TIM_DMA_CC1 ((u16)0x0200)
+#define TIM_DMA_CC2 ((u16)0x0400)
+#define TIM_DMA_CC3 ((u16)0x0800)
+#define TIM_DMA_CC4 ((u16)0x1000)
+#define TIM_DMA_COM ((u16)0x2000)
+#define TIM_DMA_Trigger ((u16)0x4000)
+
+#define IS_TIM_DMA_SOURCE(SOURCE) ((((SOURCE) & (u16)0x80FF) == 0x0000) && ((SOURCE) != 0x0000))
+
+#define IS_TIM_PERIPH_DMA(PERIPH, SOURCE) ((((((*(u32*)&(PERIPH)) == TIM2_BASE) || (((*(u32*)&(PERIPH)) == TIM3_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM4_BASE)) || (((*(u32*)&(PERIPH)) == TIM5_BASE))))&& \
+ (((SOURCE) & (u16)0xA0FF) == 0x0000) && ((SOURCE) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM1_BASE) || (((*(u32*)&(PERIPH)) == TIM8_BASE))))&& \
+ (((SOURCE) & (u16)0x80FF) == 0x0000) && ((SOURCE) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM6_BASE) || (((*(u32*)&(PERIPH)) == TIM7_BASE))))&& \
+ (((SOURCE) & (u16)0xFEFF) == 0x0000) && ((SOURCE) != 0x0000)))
+
+/* TIM External Trigger Prescaler ------------------------------------------*/
+#define TIM_ExtTRGPSC_OFF ((u16)0x0000)
+#define TIM_ExtTRGPSC_DIV2 ((u16)0x1000)
+#define TIM_ExtTRGPSC_DIV4 ((u16)0x2000)
+#define TIM_ExtTRGPSC_DIV8 ((u16)0x3000)
+
+#define IS_TIM_EXT_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ExtTRGPSC_OFF) || \
+ ((PRESCALER) == TIM_ExtTRGPSC_DIV2) || \
+ ((PRESCALER) == TIM_ExtTRGPSC_DIV4) || \
+ ((PRESCALER) == TIM_ExtTRGPSC_DIV8))
+
+/* TIM Internal Trigger Selection ------------------------------------------*/
+#define TIM_TS_ITR0 ((u16)0x0000)
+#define TIM_TS_ITR1 ((u16)0x0010)
+#define TIM_TS_ITR2 ((u16)0x0020)
+#define TIM_TS_ITR3 ((u16)0x0030)
+#define TIM_TS_TI1F_ED ((u16)0x0040)
+#define TIM_TS_TI1FP1 ((u16)0x0050)
+#define TIM_TS_TI2FP2 ((u16)0x0060)
+#define TIM_TS_ETRF ((u16)0x0070)
+
+#define IS_TIM_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \
+ ((SELECTION) == TIM_TS_ITR1) || \
+ ((SELECTION) == TIM_TS_ITR2) || \
+ ((SELECTION) == TIM_TS_ITR3) || \
+ ((SELECTION) == TIM_TS_TI1F_ED) || \
+ ((SELECTION) == TIM_TS_TI1FP1) || \
+ ((SELECTION) == TIM_TS_TI2FP2) || \
+ ((SELECTION) == TIM_TS_ETRF))
+
+#define IS_TIM_INTERNAL_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \
+ ((SELECTION) == TIM_TS_ITR1) || \
+ ((SELECTION) == TIM_TS_ITR2) || \
+ ((SELECTION) == TIM_TS_ITR3))
+
+/* TIM TIx External Clock Source -------------------------------------------*/
+#define TIM_TIxExternalCLK1Source_TI1 ((u16)0x0050)
+#define TIM_TIxExternalCLK1Source_TI2 ((u16)0x0060)
+#define TIM_TIxExternalCLK1Source_TI1ED ((u16)0x0040)
+
+#define IS_TIM_TIXCLK_SOURCE(SOURCE) (((SOURCE) == TIM_TIxExternalCLK1Source_TI1) || \
+ ((SOURCE) == TIM_TIxExternalCLK1Source_TI2) || \
+ ((SOURCE) == TIM_TIxExternalCLK1Source_TI1ED))
+
+/* TIM External Trigger Polarity -------------------------------------------*/
+#define TIM_ExtTRGPolarity_Inverted ((u16)0x8000)
+#define TIM_ExtTRGPolarity_NonInverted ((u16)0x0000)
+
+#define IS_TIM_EXT_POLARITY(POLARITY) (((POLARITY) == TIM_ExtTRGPolarity_Inverted) || \
+ ((POLARITY) == TIM_ExtTRGPolarity_NonInverted))
+
+/* TIM Prescaler Reload Mode -----------------------------------------------*/
+#define TIM_PSCReloadMode_Update ((u16)0x0000)
+#define TIM_PSCReloadMode_Immediate ((u16)0x0001)
+
+#define IS_TIM_PRESCALER_RELOAD(RELOAD) (((RELOAD) == TIM_PSCReloadMode_Update) || \
+ ((RELOAD) == TIM_PSCReloadMode_Immediate))
+
+/* TIM Forced Action -------------------------------------------------------*/
+#define TIM_ForcedAction_Active ((u16)0x0050)
+#define TIM_ForcedAction_InActive ((u16)0x0040)
+
+#define IS_TIM_FORCED_ACTION(ACTION) (((ACTION) == TIM_ForcedAction_Active) || \
+ ((ACTION) == TIM_ForcedAction_InActive))
+
+/* TIM Encoder Mode --------------------------------------------------------*/
+#define TIM_EncoderMode_TI1 ((u16)0x0001)
+#define TIM_EncoderMode_TI2 ((u16)0x0002)
+#define TIM_EncoderMode_TI12 ((u16)0x0003)
+
+#define IS_TIM_ENCODER_MODE(MODE) (((MODE) == TIM_EncoderMode_TI1) || \
+ ((MODE) == TIM_EncoderMode_TI2) || \
+ ((MODE) == TIM_EncoderMode_TI12))
+
+/* TIM Event Source --------------------------------------------------------*/
+#define TIM_EventSource_Update ((u16)0x0001)
+#define TIM_EventSource_CC1 ((u16)0x0002)
+#define TIM_EventSource_CC2 ((u16)0x0004)
+#define TIM_EventSource_CC3 ((u16)0x0008)
+#define TIM_EventSource_CC4 ((u16)0x0010)
+#define TIM_EventSource_COM ((u16)0x0020)
+#define TIM_EventSource_Trigger ((u16)0x0040)
+#define TIM_EventSource_Break ((u16)0x0080)
+
+#define IS_TIM_EVENT_SOURCE(SOURCE) ((((SOURCE) & (u16)0xFF00) == 0x0000) && ((SOURCE) != 0x0000))
+
+#define IS_TIM_PERIPH_EVENT(PERIPH, EVENT) ((((((*(u32*)&(PERIPH)) == TIM2_BASE) || (((*(u32*)&(PERIPH)) == TIM3_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM4_BASE)) || (((*(u32*)&(PERIPH)) == TIM5_BASE))))&& \
+ (((EVENT) & (u16)0xFFA0) == 0x0000) && ((EVENT) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM1_BASE) || (((*(u32*)&(PERIPH)) == TIM8_BASE))))&& \
+ (((EVENT) & (u16)0xFF00) == 0x0000) && ((EVENT) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM6_BASE) || (((*(u32*)&(PERIPH)) == TIM7_BASE))))&& \
+ (((EVENT) & (u16)0xFFFE) == 0x0000) && ((EVENT) != 0x0000)))
+
+/* TIM Update Source --------------------------------------------------------*/
+#define TIM_UpdateSource_Global ((u16)0x0000)
+#define TIM_UpdateSource_Regular ((u16)0x0001)
+
+#define IS_TIM_UPDATE_SOURCE(SOURCE) (((SOURCE) == TIM_UpdateSource_Global) || \
+ ((SOURCE) == TIM_UpdateSource_Regular))
+
+/* TIM Ouput Compare Preload State ------------------------------------------*/
+#define TIM_OCPreload_Enable ((u16)0x0008)
+#define TIM_OCPreload_Disable ((u16)0x0000)
+
+#define IS_TIM_OCPRELOAD_STATE(STATE) (((STATE) == TIM_OCPreload_Enable) || \
+ ((STATE) == TIM_OCPreload_Disable))
+
+/* TIM Ouput Compare Fast State ---------------------------------------------*/
+#define TIM_OCFast_Enable ((u16)0x0004)
+#define TIM_OCFast_Disable ((u16)0x0000)
+
+#define IS_TIM_OCFAST_STATE(STATE) (((STATE) == TIM_OCFast_Enable) || \
+ ((STATE) == TIM_OCFast_Disable))
+
+/* TIM Ouput Compare Clear State --------------------------------------------*/
+#define TIM_OCClear_Enable ((u16)0x0080)
+#define TIM_OCClear_Disable ((u16)0x0000)
+
+#define IS_TIM_OCCLEAR_STATE(STATE) (((STATE) == TIM_OCClear_Enable) || \
+ ((STATE) == TIM_OCClear_Disable))
+
+/* TIM Trigger Output Source ------------------------------------------------*/
+#define TIM_TRGOSource_Reset ((u16)0x0000)
+#define TIM_TRGOSource_Enable ((u16)0x0010)
+#define TIM_TRGOSource_Update ((u16)0x0020)
+#define TIM_TRGOSource_OC1 ((u16)0x0030)
+#define TIM_TRGOSource_OC1Ref ((u16)0x0040)
+#define TIM_TRGOSource_OC2Ref ((u16)0x0050)
+#define TIM_TRGOSource_OC3Ref ((u16)0x0060)
+#define TIM_TRGOSource_OC4Ref ((u16)0x0070)
+
+#define IS_TIM_TRGO_SOURCE(SOURCE) (((SOURCE) == TIM_TRGOSource_Reset) || \
+ ((SOURCE) == TIM_TRGOSource_Enable) || \
+ ((SOURCE) == TIM_TRGOSource_Update) || \
+ ((SOURCE) == TIM_TRGOSource_OC1) || \
+ ((SOURCE) == TIM_TRGOSource_OC1Ref) || \
+ ((SOURCE) == TIM_TRGOSource_OC2Ref) || \
+ ((SOURCE) == TIM_TRGOSource_OC3Ref) || \
+ ((SOURCE) == TIM_TRGOSource_OC4Ref))
+
+#define IS_TIM_PERIPH_TRGO(PERIPH, TRGO) (((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM6_BASE))||(((*(u32*)&(PERIPH)) == TIM7_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_Reset)) ||\
+ ((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM6_BASE))||(((*(u32*)&(PERIPH)) == TIM7_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_Enable)) ||\
+ ((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM6_BASE))||(((*(u32*)&(PERIPH)) == TIM7_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_Update)) ||\
+ ((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_OC1)) ||\
+ ((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_OC1Ref)) ||\
+ ((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_OC2Ref)) ||\
+ ((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_OC3Ref)) ||\
+ ((((*(u32*)&(PERIPH)) == TIM2_BASE)||(((*(u32*)&(PERIPH)) == TIM1_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM3_BASE))||(((*(u32*)&(PERIPH)) == TIM4_BASE))|| \
+ (((*(u32*)&(PERIPH)) == TIM5_BASE))||(((*(u32*)&(PERIPH)) == TIM8_BASE))) && \
+ ((TRGO) == TIM_TRGOSource_OC4Ref)))
+
+/* TIM Slave Mode ----------------------------------------------------------*/
+#define TIM_SlaveMode_Reset ((u16)0x0004)
+#define TIM_SlaveMode_Gated ((u16)0x0005)
+#define TIM_SlaveMode_Trigger ((u16)0x0006)
+#define TIM_SlaveMode_External1 ((u16)0x0007)
+
+#define IS_TIM_SLAVE_MODE(MODE) (((MODE) == TIM_SlaveMode_Reset) || \
+ ((MODE) == TIM_SlaveMode_Gated) || \
+ ((MODE) == TIM_SlaveMode_Trigger) || \
+ ((MODE) == TIM_SlaveMode_External1))
+
+/* TIM Master Slave Mode ---------------------------------------------------*/
+#define TIM_MasterSlaveMode_Enable ((u16)0x0080)
+#define TIM_MasterSlaveMode_Disable ((u16)0x0000)
+
+#define IS_TIM_MSM_STATE(STATE) (((STATE) == TIM_MasterSlaveMode_Enable) || \
+ ((STATE) == TIM_MasterSlaveMode_Disable))
+
+/* TIM Flags ---------------------------------------------------------------*/
+#define TIM_FLAG_Update ((u16)0x0001)
+#define TIM_FLAG_CC1 ((u16)0x0002)
+#define TIM_FLAG_CC2 ((u16)0x0004)
+#define TIM_FLAG_CC3 ((u16)0x0008)
+#define TIM_FLAG_CC4 ((u16)0x0010)
+#define TIM_FLAG_COM ((u16)0x0020)
+#define TIM_FLAG_Trigger ((u16)0x0040)
+#define TIM_FLAG_Break ((u16)0x0080)
+#define TIM_FLAG_CC1OF ((u16)0x0200)
+#define TIM_FLAG_CC2OF ((u16)0x0400)
+#define TIM_FLAG_CC3OF ((u16)0x0800)
+#define TIM_FLAG_CC4OF ((u16)0x1000)
+
+#define IS_TIM_GET_FLAG(FLAG) (((FLAG) == TIM_FLAG_Update) || \
+ ((FLAG) == TIM_FLAG_CC1) || \
+ ((FLAG) == TIM_FLAG_CC2) || \
+ ((FLAG) == TIM_FLAG_CC3) || \
+ ((FLAG) == TIM_FLAG_CC4) || \
+ ((FLAG) == TIM_FLAG_COM) || \
+ ((FLAG) == TIM_FLAG_Trigger) || \
+ ((FLAG) == TIM_FLAG_Break) || \
+ ((FLAG) == TIM_FLAG_CC1OF) || \
+ ((FLAG) == TIM_FLAG_CC2OF) || \
+ ((FLAG) == TIM_FLAG_CC3OF) || \
+ ((FLAG) == TIM_FLAG_CC4OF))
+
+#define IS_TIM_CLEAR_FLAG(PERIPH, TIM_FLAG) ((((((*(u32*)&(PERIPH)) == TIM2_BASE) || (((*(u32*)&(PERIPH)) == TIM3_BASE))||\
+ (((*(u32*)&(PERIPH)) == TIM4_BASE)) || (((*(u32*)&(PERIPH)) == TIM5_BASE))))&& \
+ (((TIM_FLAG) & (u16)0xE1A0) == 0x0000) && ((TIM_FLAG) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM1_BASE) || (((*(u32*)&(PERIPH)) == TIM8_BASE))))&& \
+ (((TIM_FLAG) & (u16)0xE100) == 0x0000) && ((TIM_FLAG) != 0x0000)) ||\
+ (((((*(u32*)&(PERIPH)) == TIM6_BASE) || (((*(u32*)&(PERIPH)) == TIM7_BASE))))&& \
+ (((TIM_FLAG) & (u16)0xFFFE) == 0x0000) && ((TIM_FLAG) != 0x0000)))
+
+#define IS_TIM_PERIPH_FLAG(PERIPH, TIM_FLAG) (((((*(u32*)&(PERIPH))==TIM2_BASE) || ((*(u32*)&(PERIPH)) == TIM3_BASE) ||\
+ ((*(u32*)&(PERIPH)) == TIM4_BASE) || ((*(u32*)&(PERIPH))==TIM5_BASE) || \
+ ((*(u32*)&(PERIPH))==TIM1_BASE) || ((*(u32*)&(PERIPH))==TIM8_BASE)) &&\
+ (((TIM_FLAG) == TIM_FLAG_CC1) || ((TIM_FLAG) == TIM_FLAG_CC2) ||\
+ ((TIM_FLAG) == TIM_FLAG_CC3) || ((TIM_FLAG) == TIM_FLAG_CC4) || \
+ ((TIM_FLAG) == TIM_FLAG_Trigger))) ||\
+ ((((*(u32*)&(PERIPH))==TIM2_BASE) || ((*(u32*)&(PERIPH)) == TIM3_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM4_BASE) || ((*(u32*)&(PERIPH))==TIM5_BASE) ||\
+ ((*(u32*)&(PERIPH))==TIM1_BASE)|| ((*(u32*)&(PERIPH))==TIM8_BASE) || \
+ ((*(u32*)&(PERIPH))==TIM7_BASE) || ((*(u32*)&(PERIPH))==TIM6_BASE)) && \
+ (((TIM_FLAG) == TIM_FLAG_Update))) ||\
+ ((((*(u32*)&(PERIPH))==TIM1_BASE) || ((*(u32*)&(PERIPH)) == TIM8_BASE)) &&\
+ (((TIM_FLAG) == TIM_FLAG_COM) || ((TIM_FLAG) == TIM_FLAG_Break))) ||\
+ ((((*(u32*)&(PERIPH))==TIM2_BASE) || ((*(u32*)&(PERIPH)) == TIM3_BASE) || \
+ ((*(u32*)&(PERIPH)) == TIM4_BASE) || ((*(u32*)&(PERIPH))==TIM5_BASE) || \
+ ((*(u32*)&(PERIPH))==TIM1_BASE) || ((*(u32*)&(PERIPH))==TIM8_BASE)) &&\
+ (((TIM_FLAG) == TIM_FLAG_CC1OF) || ((TIM_FLAG) == TIM_FLAG_CC2OF) ||\
+ ((TIM_FLAG) == TIM_FLAG_CC3OF) || ((TIM_FLAG) == TIM_FLAG_CC4OF))))
+
+/* TIM Input Capture Filer Value ---------------------------------------------*/
+#define IS_TIM_IC_FILTER(ICFILTER) ((ICFILTER) <= 0xF)
+
+/* TIM External Trigger Filter -----------------------------------------------*/
+#define IS_TIM_EXT_FILTER(EXTFILTER) ((EXTFILTER) <= 0xF)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+void TIM_DeInit(TIM_TypeDef* TIMx);
+void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct);
+void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct);
+void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct);
+void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct);
+void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct);
+void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct);
+void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct);
+void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_ITConfig(TIM_TypeDef* TIMx, u16 TIM_IT, FunctionalState NewState);
+void TIM_GenerateEvent(TIM_TypeDef* TIMx, u16 TIM_EventSource);
+void TIM_DMAConfig(TIM_TypeDef* TIMx, u16 TIM_DMABase, u16 TIM_DMABurstLength);
+void TIM_DMACmd(TIM_TypeDef* TIMx, u16 TIM_DMASource, FunctionalState NewState);
+void TIM_InternalClockConfig(TIM_TypeDef* TIMx);
+void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, u16 TIM_InputTriggerSource);
+void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, u16 TIM_TIxExternalCLKSource,
+ u16 TIM_ICPolarity, u16 ICFilter);
+void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, u16 TIM_ExtTRGPrescaler, u16 TIM_ExtTRGPolarity,
+ u16 ExtTRGFilter);
+void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, u16 TIM_ExtTRGPrescaler,
+ u16 TIM_ExtTRGPolarity, u16 ExtTRGFilter);
+void TIM_ETRConfig(TIM_TypeDef* TIMx, u16 TIM_ExtTRGPrescaler, u16 TIM_ExtTRGPolarity,
+ u16 ExtTRGFilter);
+void TIM_PrescalerConfig(TIM_TypeDef* TIMx, u16 Prescaler, u16 TIM_PSCReloadMode);
+void TIM_CounterModeConfig(TIM_TypeDef* TIMx, u16 TIM_CounterMode);
+void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, u16 TIM_InputTriggerSource);
+void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, u16 TIM_EncoderMode,
+ u16 TIM_IC1Polarity, u16 TIM_IC2Polarity);
+void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction);
+void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction);
+void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction);
+void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction);
+void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload);
+void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload);
+void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload);
+void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload);
+void TIM_OC1FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast);
+void TIM_OC2FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast);
+void TIM_OC3FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast);
+void TIM_OC4FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast);
+void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear);
+void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear);
+void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear);
+void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear);
+void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity);
+void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCNPolarity);
+void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity);
+void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCNPolarity);
+void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity);
+void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCNPolarity);
+void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity);
+void TIM_CCxCmd(TIM_TypeDef* TIMx, u16 TIM_Channel, u16 TIM_CCx);
+void TIM_CCxNCmd(TIM_TypeDef* TIMx, u16 TIM_Channel, u16 TIM_CCxN);
+void TIM_SelectOCxM(TIM_TypeDef* TIMx, u16 TIM_Channel, u16 TIM_OCMode);
+void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, u16 TIM_UpdateSource);
+void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, u16 TIM_OPMode);
+void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, u16 TIM_TRGOSource);
+void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, u16 TIM_SlaveMode);
+void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, u16 TIM_MasterSlaveMode);
+void TIM_SetCounter(TIM_TypeDef* TIMx, u16 Counter);
+void TIM_SetAutoreload(TIM_TypeDef* TIMx, u16 Autoreload);
+void TIM_SetCompare1(TIM_TypeDef* TIMx, u16 Compare1);
+void TIM_SetCompare2(TIM_TypeDef* TIMx, u16 Compare2);
+void TIM_SetCompare3(TIM_TypeDef* TIMx, u16 Compare3);
+void TIM_SetCompare4(TIM_TypeDef* TIMx, u16 Compare4);
+void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC);
+void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC);
+void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC);
+void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC);
+void TIM_SetClockDivision(TIM_TypeDef* TIMx, u16 TIM_CKD);
+u16 TIM_GetCapture1(TIM_TypeDef* TIMx);
+u16 TIM_GetCapture2(TIM_TypeDef* TIMx);
+u16 TIM_GetCapture3(TIM_TypeDef* TIMx);
+u16 TIM_GetCapture4(TIM_TypeDef* TIMx);
+u16 TIM_GetCounter(TIM_TypeDef* TIMx);
+u16 TIM_GetPrescaler(TIM_TypeDef* TIMx);
+FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, u16 TIM_FLAG);
+void TIM_ClearFlag(TIM_TypeDef* TIMx, u16 TIM_FLAG);
+ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, u16 TIM_IT);
+void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, u16 TIM_IT);
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F10x_TIM_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
+
+
+
+
+
+
+
+
diff --git a/src/stm32lib/inc/stm32f10x_type.h b/src/stm32lib/inc/stm32f10x_type.h new file mode 100644 index 0000000..895cbb2 --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_type.h @@ -0,0 +1,80 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_type.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the common data types used for the
+* STM32F10x firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_TYPE_H
+#define __STM32F10x_TYPE_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Exported types ------------------------------------------------------------*/
+typedef signed long s32;
+typedef signed short s16;
+typedef signed char s8;
+
+typedef signed long const sc32; /* Read Only */
+typedef signed short const sc16; /* Read Only */
+typedef signed char const sc8; /* Read Only */
+
+typedef volatile signed long vs32;
+typedef volatile signed short vs16;
+typedef volatile signed char vs8;
+
+typedef volatile signed long const vsc32; /* Read Only */
+typedef volatile signed short const vsc16; /* Read Only */
+typedef volatile signed char const vsc8; /* Read Only */
+
+typedef unsigned long u32;
+typedef unsigned short u16;
+typedef unsigned char u8;
+
+typedef unsigned long const uc32; /* Read Only */
+typedef unsigned short const uc16; /* Read Only */
+typedef unsigned char const uc8; /* Read Only */
+
+typedef volatile unsigned long vu32;
+typedef volatile unsigned short vu16;
+typedef volatile unsigned char vu8;
+
+typedef volatile unsigned long const vuc32; /* Read Only */
+typedef volatile unsigned short const vuc16; /* Read Only */
+typedef volatile unsigned char const vuc8; /* Read Only */
+
+//typedef enum {FALSE = 0, TRUE = !FALSE} bool;
+
+typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus;
+
+typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
+#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE))
+
+typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrorStatus;
+
+#define U8_MAX ((u8)255)
+#define S8_MAX ((s8)127)
+#define S8_MIN ((s8)-128)
+#define U16_MAX ((u16)65535u)
+#define S16_MAX ((s16)32767)
+#define S16_MIN ((s16)-32768)
+#define U32_MAX ((u32)4294967295uL)
+#define S32_MAX ((s32)2147483647)
+#define S32_MIN ((s32)-2147483648)
+
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __STM32F10x_TYPE_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_usart.h b/src/stm32lib/inc/stm32f10x_usart.h new file mode 100644 index 0000000..0731b7b --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_usart.h @@ -0,0 +1,259 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_usart.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* USART firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_USART_H
+#define __STM32F10x_USART_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* USART Init Structure definition */
+typedef struct
+{
+ u32 USART_BaudRate;
+ u16 USART_WordLength;
+ u16 USART_StopBits;
+ u16 USART_Parity;
+ u16 USART_Mode;
+ u16 USART_HardwareFlowControl;
+} USART_InitTypeDef;
+
+/* USART Clock Init Structure definition */
+typedef struct
+{
+ u16 USART_Clock;
+ u16 USART_CPOL;
+ u16 USART_CPHA;
+ u16 USART_LastBit;
+} USART_ClockInitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+#define IS_USART_ALL_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == USART1_BASE) || \
+ ((*(u32*)&(PERIPH)) == USART2_BASE) || \
+ ((*(u32*)&(PERIPH)) == USART3_BASE) || \
+ ((*(u32*)&(PERIPH)) == UART4_BASE) || \
+ ((*(u32*)&(PERIPH)) == UART5_BASE))
+
+#define IS_USART_123_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == USART1_BASE) || \
+ ((*(u32*)&(PERIPH)) == USART2_BASE) || \
+ ((*(u32*)&(PERIPH)) == USART3_BASE))
+
+#define IS_USART_1234_PERIPH(PERIPH) (((*(u32*)&(PERIPH)) == USART1_BASE) || \
+ ((*(u32*)&(PERIPH)) == USART2_BASE) || \
+ ((*(u32*)&(PERIPH)) == USART3_BASE) || \
+ ((*(u32*)&(PERIPH)) == UART4_BASE))
+
+/* USART Word Length ---------------------------------------------------------*/
+#define USART_WordLength_8b ((u16)0x0000)
+#define USART_WordLength_9b ((u16)0x1000)
+
+#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WordLength_8b) || \
+ ((LENGTH) == USART_WordLength_9b))
+
+/* USART Stop Bits -----------------------------------------------------------*/
+#define USART_StopBits_1 ((u16)0x0000)
+#define USART_StopBits_0_5 ((u16)0x1000)
+#define USART_StopBits_2 ((u16)0x2000)
+#define USART_StopBits_1_5 ((u16)0x3000)
+
+#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_StopBits_1) || \
+ ((STOPBITS) == USART_StopBits_0_5) || \
+ ((STOPBITS) == USART_StopBits_2) || \
+ ((STOPBITS) == USART_StopBits_1_5))
+/* USART Parity --------------------------------------------------------------*/
+#define USART_Parity_No ((u16)0x0000)
+#define USART_Parity_Even ((u16)0x0400)
+#define USART_Parity_Odd ((u16)0x0600)
+
+#define IS_USART_PARITY(PARITY) (((PARITY) == USART_Parity_No) || \
+ ((PARITY) == USART_Parity_Even) || \
+ ((PARITY) == USART_Parity_Odd))
+
+/* USART Mode ----------------------------------------------------------------*/
+#define USART_Mode_Rx ((u16)0x0004)
+#define USART_Mode_Tx ((u16)0x0008)
+
+#define IS_USART_MODE(MODE) ((((MODE) & (u16)0xFFF3) == 0x00) && ((MODE) != (u16)0x00))
+
+/* USART Hardware Flow Control -----------------------------------------------*/
+#define USART_HardwareFlowControl_None ((u16)0x0000)
+#define USART_HardwareFlowControl_RTS ((u16)0x0100)
+#define USART_HardwareFlowControl_CTS ((u16)0x0200)
+#define USART_HardwareFlowControl_RTS_CTS ((u16)0x0300)
+
+#define IS_USART_HARDWARE_FLOW_CONTROL(CONTROL)\
+ (((CONTROL) == USART_HardwareFlowControl_None) || \
+ ((CONTROL) == USART_HardwareFlowControl_RTS) || \
+ ((CONTROL) == USART_HardwareFlowControl_CTS) || \
+ ((CONTROL) == USART_HardwareFlowControl_RTS_CTS))
+
+#define IS_USART_PERIPH_HFC(PERIPH, HFC) ((((*(u32*)&(PERIPH)) != UART4_BASE) && \
+ ((*(u32*)&(PERIPH)) != UART5_BASE)) \
+ || ((HFC) == USART_HardwareFlowControl_None))
+
+/* USART Clock ---------------------------------------------------------------*/
+#define USART_Clock_Disable ((u16)0x0000)
+#define USART_Clock_Enable ((u16)0x0800)
+
+#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_Clock_Disable) || \
+ ((CLOCK) == USART_Clock_Enable))
+
+/* USART Clock Polarity ------------------------------------------------------*/
+#define USART_CPOL_Low ((u16)0x0000)
+#define USART_CPOL_High ((u16)0x0400)
+
+#define IS_USART_CPOL(CPOL) (((CPOL) == USART_CPOL_Low) || ((CPOL) == USART_CPOL_High))
+
+/* USART Clock Phase ---------------------------------------------------------*/
+#define USART_CPHA_1Edge ((u16)0x0000)
+#define USART_CPHA_2Edge ((u16)0x0200)
+#define IS_USART_CPHA(CPHA) (((CPHA) == USART_CPHA_1Edge) || ((CPHA) == USART_CPHA_2Edge))
+
+/* USART Last Bit ------------------------------------------------------------*/
+#define USART_LastBit_Disable ((u16)0x0000)
+#define USART_LastBit_Enable ((u16)0x0100)
+
+#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LastBit_Disable) || \
+ ((LASTBIT) == USART_LastBit_Enable))
+
+/* USART Interrupt definition ------------------------------------------------*/
+#define USART_IT_PE ((u16)0x0028)
+#define USART_IT_TXE ((u16)0x0727)
+#define USART_IT_TC ((u16)0x0626)
+#define USART_IT_RXNE ((u16)0x0525)
+#define USART_IT_IDLE ((u16)0x0424)
+#define USART_IT_LBD ((u16)0x0846)
+#define USART_IT_CTS ((u16)0x096A)
+#define USART_IT_ERR ((u16)0x0060)
+#define USART_IT_ORE ((u16)0x0360)
+#define USART_IT_NE ((u16)0x0260)
+#define USART_IT_FE ((u16)0x0160)
+
+#define IS_USART_CONFIG_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \
+ ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
+ ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \
+ ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ERR))
+
+#define IS_USART_GET_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \
+ ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
+ ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \
+ ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ORE) || \
+ ((IT) == USART_IT_NE) || ((IT) == USART_IT_FE))
+
+#define IS_USART_CLEAR_IT(IT) (((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
+ ((IT) == USART_IT_LBD) || ((IT) == USART_IT_CTS))
+
+#define IS_USART_PERIPH_IT(PERIPH, USART_IT) ((((*(u32*)&(PERIPH)) != UART4_BASE) && \
+ ((*(u32*)&(PERIPH)) != UART5_BASE)) \
+ || ((USART_IT) != USART_IT_CTS))
+
+/* USART DMA Requests --------------------------------------------------------*/
+#define USART_DMAReq_Tx ((u16)0x0080)
+#define USART_DMAReq_Rx ((u16)0x0040)
+
+#define IS_USART_DMAREQ(DMAREQ) ((((DMAREQ) & (u16)0xFF3F) == 0x00) && ((DMAREQ) != (u16)0x00))
+
+/* USART WakeUp methods ------------------------------------------------------*/
+#define USART_WakeUp_IdleLine ((u16)0x0000)
+#define USART_WakeUp_AddressMark ((u16)0x0800)
+
+#define IS_USART_WAKEUP(WAKEUP) (((WAKEUP) == USART_WakeUp_IdleLine) || \
+ ((WAKEUP) == USART_WakeUp_AddressMark))
+
+/* USART LIN Break Detection Length ------------------------------------------*/
+#define USART_LINBreakDetectLength_10b ((u16)0x0000)
+#define USART_LINBreakDetectLength_11b ((u16)0x0020)
+
+#define IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH) \
+ (((LENGTH) == USART_LINBreakDetectLength_10b) || \
+ ((LENGTH) == USART_LINBreakDetectLength_11b))
+
+/* USART IrDA Low Power ------------------------------------------------------*/
+#define USART_IrDAMode_LowPower ((u16)0x0004)
+#define USART_IrDAMode_Normal ((u16)0x0000)
+
+#define IS_USART_IRDA_MODE(MODE) (((MODE) == USART_IrDAMode_LowPower) || \
+ ((MODE) == USART_IrDAMode_Normal))
+
+/* USART Flags ---------------------------------------------------------------*/
+#define USART_FLAG_CTS ((u16)0x0200)
+#define USART_FLAG_LBD ((u16)0x0100)
+#define USART_FLAG_TXE ((u16)0x0080)
+#define USART_FLAG_TC ((u16)0x0040)
+#define USART_FLAG_RXNE ((u16)0x0020)
+#define USART_FLAG_IDLE ((u16)0x0010)
+#define USART_FLAG_ORE ((u16)0x0008)
+#define USART_FLAG_NE ((u16)0x0004)
+#define USART_FLAG_FE ((u16)0x0002)
+#define USART_FLAG_PE ((u16)0x0001)
+
+#define IS_USART_FLAG(FLAG) (((FLAG) == USART_FLAG_PE) || ((FLAG) == USART_FLAG_TXE) || \
+ ((FLAG) == USART_FLAG_TC) || ((FLAG) == USART_FLAG_RXNE) || \
+ ((FLAG) == USART_FLAG_IDLE) || ((FLAG) == USART_FLAG_LBD) || \
+ ((FLAG) == USART_FLAG_CTS) || ((FLAG) == USART_FLAG_ORE) || \
+ ((FLAG) == USART_FLAG_NE) || ((FLAG) == USART_FLAG_FE))
+
+#define IS_USART_CLEAR_FLAG(FLAG) ((((FLAG) & (u16)0xFC9F) == 0x00) && ((FLAG) != (u16)0x00))
+
+#define IS_USART_PERIPH_FLAG(PERIPH, USART_FLAG) ((((*(u32*)&(PERIPH)) != UART4_BASE) &&\
+ ((*(u32*)&(PERIPH)) != UART5_BASE)) \
+ || ((USART_FLAG) != USART_FLAG_CTS))
+
+#define IS_USART_BAUDRATE(BAUDRATE) (((BAUDRATE) > 0) && ((BAUDRATE) < 0x0044AA21))
+#define IS_USART_ADDRESS(ADDRESS) ((ADDRESS) <= 0xF)
+#define IS_USART_DATA(DATA) ((DATA) <= 0x1FF)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+#ifdef __cplusplus
+extern "C" {
+#endif
+void USART_DeInit(USART_TypeDef* USARTx);
+void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct);
+void USART_StructInit(USART_InitTypeDef* USART_InitStruct);
+void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct);
+void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct);
+void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_ITConfig(USART_TypeDef* USARTx, u16 USART_IT, FunctionalState NewState);
+void USART_DMACmd(USART_TypeDef* USARTx, u16 USART_DMAReq, FunctionalState NewState);
+void USART_SetAddress(USART_TypeDef* USARTx, u8 USART_Address);
+void USART_WakeUpConfig(USART_TypeDef* USARTx, u16 USART_WakeUp);
+void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, u16 USART_LINBreakDetectLength);
+void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_SendData(USART_TypeDef* USARTx, u16 Data);
+u16 USART_ReceiveData(USART_TypeDef* USARTx);
+void USART_SendBreak(USART_TypeDef* USARTx);
+void USART_SetGuardTime(USART_TypeDef* USARTx, u8 USART_GuardTime);
+void USART_SetPrescaler(USART_TypeDef* USARTx, u8 USART_Prescaler);
+void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_IrDAConfig(USART_TypeDef* USARTx, u16 USART_IrDAMode);
+void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState);
+FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, u16 USART_FLAG);
+void USART_ClearFlag(USART_TypeDef* USARTx, u16 USART_FLAG);
+ITStatus USART_GetITStatus(USART_TypeDef* USARTx, u16 USART_IT);
+void USART_ClearITPendingBit(USART_TypeDef* USARTx, u16 USART_IT);
+
+#ifdef __cplusplus
+}
+#endif
+#endif /* __STM32F10x_USART_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/inc/stm32f10x_wwdg.h b/src/stm32lib/inc/stm32f10x_wwdg.h new file mode 100644 index 0000000..3c5339e --- /dev/null +++ b/src/stm32lib/inc/stm32f10x_wwdg.h @@ -0,0 +1,54 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_wwdg.h
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file contains all the functions prototypes for the
+* WWDG firmware library.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_WWDG_H
+#define __STM32F10x_WWDG_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_map.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* WWDG Prescaler */
+#define WWDG_Prescaler_1 ((u32)0x00000000)
+#define WWDG_Prescaler_2 ((u32)0x00000080)
+#define WWDG_Prescaler_4 ((u32)0x00000100)
+#define WWDG_Prescaler_8 ((u32)0x00000180)
+
+#define IS_WWDG_PRESCALER(PRESCALER) (((PRESCALER) == WWDG_Prescaler_1) || \
+ ((PRESCALER) == WWDG_Prescaler_2) || \
+ ((PRESCALER) == WWDG_Prescaler_4) || \
+ ((PRESCALER) == WWDG_Prescaler_8))
+
+#define IS_WWDG_WINDOW_VALUE(VALUE) ((VALUE) <= 0x7F)
+
+#define IS_WWDG_COUNTER(COUNTER) (((COUNTER) >= 0x40) && ((COUNTER) <= 0x7F))
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+void WWDG_DeInit(void);
+void WWDG_SetPrescaler(u32 WWDG_Prescaler);
+void WWDG_SetWindowValue(u8 WindowValue);
+void WWDG_EnableIT(void);
+void WWDG_SetCounter(u8 Counter);
+void WWDG_Enable(u8 Counter);
+FlagStatus WWDG_GetFlagStatus(void);
+void WWDG_ClearFlag(void);
+
+#endif /* __STM32F10x_WWDG_H */
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_adc.c b/src/stm32lib/src/stm32f10x_adc.c new file mode 100644 index 0000000..413c920 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_adc.c @@ -0,0 +1,1402 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_adc.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the ADC firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_adc.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ADC DISCNUM mask */
+#define CR1_DISCNUM_Reset ((u32)0xFFFF1FFF)
+
+/* ADC DISCEN mask */
+#define CR1_DISCEN_Set ((u32)0x00000800)
+#define CR1_DISCEN_Reset ((u32)0xFFFFF7FF)
+
+/* ADC JAUTO mask */
+#define CR1_JAUTO_Set ((u32)0x00000400)
+#define CR1_JAUTO_Reset ((u32)0xFFFFFBFF)
+
+/* ADC JDISCEN mask */
+#define CR1_JDISCEN_Set ((u32)0x00001000)
+#define CR1_JDISCEN_Reset ((u32)0xFFFFEFFF)
+
+/* ADC AWDCH mask */
+#define CR1_AWDCH_Reset ((u32)0xFFFFFFE0)
+
+/* ADC Analog watchdog enable mode mask */
+#define CR1_AWDMode_Reset ((u32)0xFF3FFDFF)
+
+/* CR1 register Mask */
+#define CR1_CLEAR_Mask ((u32)0xFFF0FEFF)
+
+/* ADC ADON mask */
+#define CR2_ADON_Set ((u32)0x00000001)
+#define CR2_ADON_Reset ((u32)0xFFFFFFFE)
+
+/* ADC DMA mask */
+#define CR2_DMA_Set ((u32)0x00000100)
+#define CR2_DMA_Reset ((u32)0xFFFFFEFF)
+
+/* ADC RSTCAL mask */
+#define CR2_RSTCAL_Set ((u32)0x00000008)
+
+/* ADC CAL mask */
+#define CR2_CAL_Set ((u32)0x00000004)
+
+/* ADC SWSTART mask */
+#define CR2_SWSTART_Set ((u32)0x00400000)
+
+/* ADC EXTTRIG mask */
+#define CR2_EXTTRIG_Set ((u32)0x00100000)
+#define CR2_EXTTRIG_Reset ((u32)0xFFEFFFFF)
+
+/* ADC Software start mask */
+#define CR2_EXTTRIG_SWSTART_Set ((u32)0x00500000)
+#define CR2_EXTTRIG_SWSTART_Reset ((u32)0xFFAFFFFF)
+
+/* ADC JEXTSEL mask */
+#define CR2_JEXTSEL_Reset ((u32)0xFFFF8FFF)
+
+/* ADC JEXTTRIG mask */
+#define CR2_JEXTTRIG_Set ((u32)0x00008000)
+#define CR2_JEXTTRIG_Reset ((u32)0xFFFF7FFF)
+
+/* ADC JSWSTART mask */
+#define CR2_JSWSTART_Set ((u32)0x00200000)
+
+/* ADC injected software start mask */
+#define CR2_JEXTTRIG_JSWSTART_Set ((u32)0x00208000)
+#define CR2_JEXTTRIG_JSWSTART_Reset ((u32)0xFFDF7FFF)
+
+/* ADC TSPD mask */
+#define CR2_TSVREFE_Set ((u32)0x00800000)
+#define CR2_TSVREFE_Reset ((u32)0xFF7FFFFF)
+
+/* CR2 register Mask */
+#define CR2_CLEAR_Mask ((u32)0xFFF1F7FD)
+
+/* ADC SQx mask */
+#define SQR3_SQ_Set ((u32)0x0000001F)
+#define SQR2_SQ_Set ((u32)0x0000001F)
+#define SQR1_SQ_Set ((u32)0x0000001F)
+
+/* SQR1 register Mask */
+#define SQR1_CLEAR_Mask ((u32)0xFF0FFFFF)
+
+/* ADC JSQx mask */
+#define JSQR_JSQ_Set ((u32)0x0000001F)
+
+/* ADC JL mask */
+#define JSQR_JL_Set ((u32)0x00300000)
+#define JSQR_JL_Reset ((u32)0xFFCFFFFF)
+
+/* ADC SMPx mask */
+#define SMPR1_SMP_Set ((u32)0x00000007)
+#define SMPR2_SMP_Set ((u32)0x00000007)
+
+/* ADC JDRx registers offset */
+#define JDR_Offset ((u8)0x28)
+
+/* ADC1 DR register base address */
+#define DR_ADDRESS ((u32)0x4001244C)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : ADC_DeInit
+* Description : Deinitializes the ADCx peripheral registers to their default
+* reset values.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_DeInit(ADC_TypeDef* ADCx)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ switch (*(u32*)&ADCx)
+ {
+ case ADC1_BASE:
+ /* Enable ADC1 reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, ENABLE);
+ /* Release ADC1 from reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, DISABLE);
+ break;
+
+ case ADC2_BASE:
+ /* Enable ADC2 reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, ENABLE);
+ /* Release ADC2 from reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, DISABLE);
+ break;
+
+ case ADC3_BASE:
+ /* Enable ADC3 reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, ENABLE);
+ /* Release ADC3 from reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, DISABLE);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_Init
+* Description : Initializes the ADCx peripheral according to the specified parameters
+* in the ADC_InitStruct.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_InitStruct: pointer to an ADC_InitTypeDef structure that
+* contains the configuration information for the specified
+* ADC peripheral.
+* Output : None
+* Return : None
+******************************************************************************/
+void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct)
+{
+ u32 tmpreg1 = 0;
+ u8 tmpreg2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_MODE(ADC_InitStruct->ADC_Mode));
+ assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ScanConvMode));
+ assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ContinuousConvMode));
+ assert_param(IS_ADC_EXT_TRIG(ADC_InitStruct->ADC_ExternalTrigConv));
+ assert_param(IS_ADC_DATA_ALIGN(ADC_InitStruct->ADC_DataAlign));
+ assert_param(IS_ADC_REGULAR_LENGTH(ADC_InitStruct->ADC_NbrOfChannel));
+
+ /*---------------------------- ADCx CR1 Configuration -----------------*/
+ /* Get the ADCx CR1 value */
+ tmpreg1 = ADCx->CR1;
+ /* Clear DUALMOD and SCAN bits */
+ tmpreg1 &= CR1_CLEAR_Mask;
+ /* Configure ADCx: Dual mode and scan conversion mode */
+ /* Set DUALMOD bits according to ADC_Mode value */
+ /* Set SCAN bit according to ADC_ScanConvMode value */
+ tmpreg1 |= (u32)(ADC_InitStruct->ADC_Mode | ((u32)ADC_InitStruct->ADC_ScanConvMode << 8));
+ /* Write to ADCx CR1 */
+ ADCx->CR1 = tmpreg1;
+
+ /*---------------------------- ADCx CR2 Configuration -----------------*/
+ /* Get the ADCx CR2 value */
+ tmpreg1 = ADCx->CR2;
+ /* Clear CONT, ALIGN and EXTSEL bits */
+ tmpreg1 &= CR2_CLEAR_Mask;
+ /* Configure ADCx: external trigger event and continuous conversion mode */
+ /* Set ALIGN bit according to ADC_DataAlign value */
+ /* Set EXTSEL bits according to ADC_ExternalTrigConv value */
+ /* Set CONT bit according to ADC_ContinuousConvMode value */
+ tmpreg1 |= (u32)(ADC_InitStruct->ADC_DataAlign | ADC_InitStruct->ADC_ExternalTrigConv |
+ ((u32)ADC_InitStruct->ADC_ContinuousConvMode << 1));
+ /* Write to ADCx CR2 */
+ ADCx->CR2 = tmpreg1;
+
+ /*---------------------------- ADCx SQR1 Configuration -----------------*/
+ /* Get the ADCx SQR1 value */
+ tmpreg1 = ADCx->SQR1;
+ /* Clear L bits */
+ tmpreg1 &= SQR1_CLEAR_Mask;
+ /* Configure ADCx: regular channel sequence length */
+ /* Set L bits according to ADC_NbrOfChannel value */
+ tmpreg2 |= (ADC_InitStruct->ADC_NbrOfChannel - 1);
+ tmpreg1 |= ((u32)tmpreg2 << 20);
+ /* Write to ADCx SQR1 */
+ ADCx->SQR1 = tmpreg1;
+}
+
+/*******************************************************************************
+* Function Name : ADC_StructInit
+* Description : Fills each ADC_InitStruct member with its default value.
+* Input : ADC_InitStruct : pointer to an ADC_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct)
+{
+ /* Reset ADC init structure parameters values */
+ /* Initialize the ADC_Mode member */
+ ADC_InitStruct->ADC_Mode = ADC_Mode_Independent;
+
+ /* initialize the ADC_ScanConvMode member */
+ ADC_InitStruct->ADC_ScanConvMode = DISABLE;
+
+ /* Initialize the ADC_ContinuousConvMode member */
+ ADC_InitStruct->ADC_ContinuousConvMode = DISABLE;
+
+ /* Initialize the ADC_ExternalTrigConv member */
+ ADC_InitStruct->ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1;
+
+ /* Initialize the ADC_DataAlign member */
+ ADC_InitStruct->ADC_DataAlign = ADC_DataAlign_Right;
+
+ /* Initialize the ADC_NbrOfChannel member */
+ ADC_InitStruct->ADC_NbrOfChannel = 1;
+}
+
+/*******************************************************************************
+* Function Name : ADC_Cmd
+* Description : Enables or disables the specified ADC peripheral.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the ADCx peripheral. This parameter
+* can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Set the ADON bit to wake up the ADC from power down mode */
+ ADCx->CR2 |= CR2_ADON_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC peripheral */
+ ADCx->CR2 &= CR2_ADON_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_DMACmd
+* Description : Enables or disables the specified ADC DMA request.
+* Input : - ADCx: where x can be 1 or 3 to select the ADC peripheral.
+* Note: ADC2 hasn't a DMA capability.
+* - NewState: new state of the selected ADC DMA transfer.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_DMA_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC DMA request */
+ ADCx->CR2 |= CR2_DMA_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC DMA request */
+ ADCx->CR2 &= CR2_DMA_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_ITConfig
+* Description : Enables or disables the specified ADC interrupts.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_IT: specifies the ADC interrupt sources to be enabled
+* or disabled.
+* This parameter can be any combination of the following values:
+* - ADC_IT_EOC: End of conversion interrupt mask
+* - ADC_IT_AWD: Analog watchdog interrupt mask
+* - ADC_IT_JEOC: End of injected conversion interrupt mask
+* - NewState: new state of the specified ADC interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_ITConfig(ADC_TypeDef* ADCx, u16 ADC_IT, FunctionalState NewState)
+{
+ u8 itmask = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+ assert_param(IS_ADC_IT(ADC_IT));
+
+ /* Get the ADC IT index */
+ itmask = (u8)ADC_IT;
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC interrupts */
+ ADCx->CR1 |= itmask;
+ }
+ else
+ {
+ /* Disable the selected ADC interrupts */
+ ADCx->CR1 &= (~(u32)itmask);
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_ResetCalibration
+* Description : Resets the selected ADC calibration registers.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_ResetCalibration(ADC_TypeDef* ADCx)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ /* Resets the selected ADC calibartion registers */
+ ADCx->CR2 |= CR2_RSTCAL_Set;
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetResetCalibrationStatus
+* Description : Gets the selected ADC reset calibration registers status.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : The new state of ADC reset calibration registers (SET or RESET).
+*******************************************************************************/
+FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ /* Check the status of RSTCAL bit */
+ if ((ADCx->CR2 & CR2_RSTCAL_Set) != (u32)RESET)
+ {
+ /* RSTCAL bit is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* RSTCAL bit is reset */
+ bitstatus = RESET;
+ }
+
+ /* Return the RSTCAL bit status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : ADC_StartCalibration
+* Description : Starts the selected ADC calibration process.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_StartCalibration(ADC_TypeDef* ADCx)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ /* Enable the selected ADC calibration process */
+ ADCx->CR2 |= CR2_CAL_Set;
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetCalibrationStatus
+* Description : Gets the selected ADC calibration status.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : The new state of ADC calibration (SET or RESET).
+*******************************************************************************/
+FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ /* Check the status of CAL bit */
+ if ((ADCx->CR2 & CR2_CAL_Set) != (u32)RESET)
+ {
+ /* CAL bit is set: calibration on going */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* CAL bit is reset: end of calibration */
+ bitstatus = RESET;
+ }
+
+ /* Return the CAL bit status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : ADC_SoftwareStartConvCmd
+* Description : Enables or disables the selected ADC software start conversion .
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the selected ADC software start conversion.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC conversion on external event and start the selected
+ ADC conversion */
+ ADCx->CR2 |= CR2_EXTTRIG_SWSTART_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC conversion on external event and stop the selected
+ ADC conversion */
+ ADCx->CR2 &= CR2_EXTTRIG_SWSTART_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetSoftwareStartConvStatus
+* Description : Gets the selected ADC Software start conversion Status.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : The new state of ADC software start conversion (SET or RESET).
+*******************************************************************************/
+FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ /* Check the status of SWSTART bit */
+ if ((ADCx->CR2 & CR2_SWSTART_Set) != (u32)RESET)
+ {
+ /* SWSTART bit is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* SWSTART bit is reset */
+ bitstatus = RESET;
+ }
+
+ /* Return the SWSTART bit status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : ADC_DiscModeChannelCountConfig
+* Description : Configures the discontinuous mode for the selected ADC regular
+* group channel.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - Number: specifies the discontinuous mode regular channel
+* count value. This number must be between 1 and 8.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, u8 Number)
+{
+ u32 tmpreg1 = 0;
+ u32 tmpreg2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_REGULAR_DISC_NUMBER(Number));
+
+ /* Get the old register value */
+ tmpreg1 = ADCx->CR1;
+ /* Clear the old discontinuous mode channel count */
+ tmpreg1 &= CR1_DISCNUM_Reset;
+ /* Set the discontinuous mode channel count */
+ tmpreg2 = Number - 1;
+ tmpreg1 |= tmpreg2 << 13;
+ /* Store the new register value */
+ ADCx->CR1 = tmpreg1;
+}
+
+/*******************************************************************************
+* Function Name : ADC_DiscModeCmd
+* Description : Enables or disables the discontinuous mode on regular group
+* channel for the specified ADC
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the selected ADC discontinuous mode
+* on regular group channel.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC regular discontinuous mode */
+ ADCx->CR1 |= CR1_DISCEN_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC regular discontinuous mode */
+ ADCx->CR1 &= CR1_DISCEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_RegularChannelConfig
+* Description : Configures for the selected ADC regular channel its corresponding
+* rank in the sequencer and its sample time.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_Channel: the ADC channel to configure.
+* This parameter can be one of the following values:
+* - ADC_Channel_0: ADC Channel0 selected
+* - ADC_Channel_1: ADC Channel1 selected
+* - ADC_Channel_2: ADC Channel2 selected
+* - ADC_Channel_3: ADC Channel3 selected
+* - ADC_Channel_4: ADC Channel4 selected
+* - ADC_Channel_5: ADC Channel5 selected
+* - ADC_Channel_6: ADC Channel6 selected
+* - ADC_Channel_7: ADC Channel7 selected
+* - ADC_Channel_8: ADC Channel8 selected
+* - ADC_Channel_9: ADC Channel9 selected
+* - ADC_Channel_10: ADC Channel10 selected
+* - ADC_Channel_11: ADC Channel11 selected
+* - ADC_Channel_12: ADC Channel12 selected
+* - ADC_Channel_13: ADC Channel13 selected
+* - ADC_Channel_14: ADC Channel14 selected
+* - ADC_Channel_15: ADC Channel15 selected
+* - ADC_Channel_16: ADC Channel16 selected
+* - ADC_Channel_17: ADC Channel17 selected
+* - Rank: The rank in the regular group sequencer. This parameter
+* must be between 1 to 16.
+* - ADC_SampleTime: The sample time value to be set for the
+* selected channel.
+* This parameter can be one of the following values:
+* - ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles
+* - ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles
+* - ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles
+* - ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles
+* - ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles
+* - ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles
+* - ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles
+* - ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel, u8 Rank, u8 ADC_SampleTime)
+{
+ u32 tmpreg1 = 0, tmpreg2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_CHANNEL(ADC_Channel));
+ assert_param(IS_ADC_REGULAR_RANK(Rank));
+ assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime));
+
+ /* if ADC_Channel_10 ... ADC_Channel_17 is selected */
+ if (ADC_Channel > ADC_Channel_9)
+ {
+ /* Get the old register value */
+ tmpreg1 = ADCx->SMPR1;
+ /* Calculate the mask to clear */
+ tmpreg2 = SMPR1_SMP_Set << (3 * (ADC_Channel - 10));
+ /* Clear the old discontinuous mode channel count */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set */
+ tmpreg2 = (u32)ADC_SampleTime << (3 * (ADC_Channel - 10));
+ /* Set the discontinuous mode channel count */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->SMPR1 = tmpreg1;
+ }
+ else /* ADC_Channel include in ADC_Channel_[0..9] */
+ {
+ /* Get the old register value */
+ tmpreg1 = ADCx->SMPR2;
+ /* Calculate the mask to clear */
+ tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel);
+ /* Clear the old discontinuous mode channel count */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set */
+ tmpreg2 = (u32)ADC_SampleTime << (3 * ADC_Channel);
+ /* Set the discontinuous mode channel count */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->SMPR2 = tmpreg1;
+ }
+ /* For Rank 1 to 6 */
+ if (Rank < 7)
+ {
+ /* Get the old register value */
+ tmpreg1 = ADCx->SQR3;
+ /* Calculate the mask to clear */
+ tmpreg2 = SQR3_SQ_Set << (5 * (Rank - 1));
+ /* Clear the old SQx bits for the selected rank */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set */
+ tmpreg2 = (u32)ADC_Channel << (5 * (Rank - 1));
+ /* Set the SQx bits for the selected rank */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->SQR3 = tmpreg1;
+ }
+ /* For Rank 7 to 12 */
+ else if (Rank < 13)
+ {
+ /* Get the old register value */
+ tmpreg1 = ADCx->SQR2;
+ /* Calculate the mask to clear */
+ tmpreg2 = SQR2_SQ_Set << (5 * (Rank - 7));
+ /* Clear the old SQx bits for the selected rank */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set */
+ tmpreg2 = (u32)ADC_Channel << (5 * (Rank - 7));
+ /* Set the SQx bits for the selected rank */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->SQR2 = tmpreg1;
+ }
+ /* For Rank 13 to 16 */
+ else
+ {
+ /* Get the old register value */
+ tmpreg1 = ADCx->SQR1;
+ /* Calculate the mask to clear */
+ tmpreg2 = SQR1_SQ_Set << (5 * (Rank - 13));
+ /* Clear the old SQx bits for the selected rank */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set */
+ tmpreg2 = (u32)ADC_Channel << (5 * (Rank - 13));
+ /* Set the SQx bits for the selected rank */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->SQR1 = tmpreg1;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_ExternalTrigConvCmd
+* Description : Enables or disables the ADCx conversion through external trigger.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the selected ADC external trigger
+* start of conversion.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC conversion on external event */
+ ADCx->CR2 |= CR2_EXTTRIG_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC conversion on external event */
+ ADCx->CR2 &= CR2_EXTTRIG_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetConversionValue
+* Description : Returns the last ADCx conversion result data for regular channel.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : The Data conversion value.
+*******************************************************************************/
+u16 ADC_GetConversionValue(ADC_TypeDef* ADCx)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ /* Return the selected ADC conversion value */
+ return (u16) ADCx->DR;
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetDualModeConversionValue
+* Description : Returns the last ADC1 and ADC2 conversion result data in dual mode.
+* Output : None
+* Return : The Data conversion value.
+*******************************************************************************/
+u32 ADC_GetDualModeConversionValue(void)
+{
+ /* Return the dual mode conversion value */
+ return (*(vu32 *) DR_ADDRESS);
+}
+
+/*******************************************************************************
+* Function Name : ADC_AutoInjectedConvCmd
+* Description : Enables or disables the selected ADC automatic injected group
+* conversion after regular one.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the selected ADC auto injected
+* conversion
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC automatic injected group conversion */
+ ADCx->CR1 |= CR1_JAUTO_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC automatic injected group conversion */
+ ADCx->CR1 &= CR1_JAUTO_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_InjectedDiscModeCmd
+* Description : Enables or disables the discontinuous mode for injected group
+* channel for the specified ADC
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the selected ADC discontinuous mode
+* on injected group channel.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC injected discontinuous mode */
+ ADCx->CR1 |= CR1_JDISCEN_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC injected discontinuous mode */
+ ADCx->CR1 &= CR1_JDISCEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_ExternalTrigInjectedConvConfig
+* Description : Configures the ADCx external trigger for injected channels conversion.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_ExternalTrigInjecConv: specifies the ADC trigger to
+* start injected conversion.
+* This parameter can be one of the following values:
+* - ADC_ExternalTrigInjecConv_T1_TRGO: Timer1 TRGO event
+* selected (for ADC1, ADC2 and ADC3)
+* - ADC_ExternalTrigInjecConv_T1_CC4: Timer1 capture
+* compare4 selected (for ADC1, ADC2 and ADC3)
+* - ADC_ExternalTrigInjecConv_T2_TRGO: Timer2 TRGO event
+* selected (for ADC1 and ADC2)
+* - ADC_External TrigInjecConv_T2_CC1: Timer2 capture
+* compare1 selected (for ADC1 and ADC2)
+* - ADC_ExternalTrigInjecConv_T3_CC4: Timer3 capture
+* compare4 selected (for ADC1 and ADC2)
+* - ADC_ExternalTrigInjecConv_T4_TRGO: Timer4 TRGO event
+* selected (for ADC1 and ADC2)
+* - ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4: External
+* interrupt line 15 or Timer8 capture compare4 event selected
+* (for ADC1 and ADC2)
+* - ADC_External TrigInjecConv_T4_CC3: Timer4 capture
+* compare3 selected (for ADC3 only)
+* - ADC_External TrigInjecConv_T8_CC2: Timer8 capture
+* compare2 selected (for ADC3 only)
+* - ADC_External TrigInjecConv_T8_CC4: Timer8 capture
+* compare4 selected (for ADC3 only)
+* - ADC_ExternalTrigInjecConv_T5_TRGO: Timer5 TRGO event
+* selected (for ADC3 only)
+* - ADC_External TrigInjecConv_T5_CC4: Timer5 capture
+* compare4 selected (for ADC3 only)
+* - ADC_ExternalTrigInjecConv_None: Injected conversion
+* started by software and not by external trigger (for
+* ADC1, ADC2 and ADC3)
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, u32 ADC_ExternalTrigInjecConv)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_EXT_INJEC_TRIG(ADC_ExternalTrigInjecConv));
+
+ /* Get the old register value */
+ tmpreg = ADCx->CR2;
+ /* Clear the old external event selection for injected group */
+ tmpreg &= CR2_JEXTSEL_Reset;
+ /* Set the external event selection for injected group */
+ tmpreg |= ADC_ExternalTrigInjecConv;
+ /* Store the new register value */
+ ADCx->CR2 = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : ADC_ExternalTrigInjectedConvCmd
+* Description : Enables or disables the ADCx injected channels conversion
+* through external trigger
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the selected ADC external trigger
+* start of injected conversion.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC external event selection for injected group */
+ ADCx->CR2 |= CR2_JEXTTRIG_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC external event selection for injected group */
+ ADCx->CR2 &= CR2_JEXTTRIG_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_SoftwareStartInjectedConvCmd
+* Description : Enables or disables the selected ADC start of the injected
+* channels conversion.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - NewState: new state of the selected ADC software start
+* injected conversion.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected ADC conversion for injected group on external event and start the selected
+ ADC injected conversion */
+ ADCx->CR2 |= CR2_JEXTTRIG_JSWSTART_Set;
+ }
+ else
+ {
+ /* Disable the selected ADC conversion on external event for injected group and stop the selected
+ ADC injected conversion */
+ ADCx->CR2 &= CR2_JEXTTRIG_JSWSTART_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetSoftwareStartInjectedConvCmdStatus
+* Description : Gets the selected ADC Software start injected conversion Status.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* Output : None
+* Return : The new state of ADC software start injected conversion (SET or RESET).
+*******************************************************************************/
+FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+
+ /* Check the status of JSWSTART bit */
+ if ((ADCx->CR2 & CR2_JSWSTART_Set) != (u32)RESET)
+ {
+ /* JSWSTART bit is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* JSWSTART bit is reset */
+ bitstatus = RESET;
+ }
+
+ /* Return the JSWSTART bit status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : ADC_InjectedChannelConfig
+* Description : Configures for the selected ADC injected channel its corresponding
+* rank in the sequencer and its sample time.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_Channel: the ADC channel to configure.
+* This parameter can be one of the following values:
+* - ADC_Channel_0: ADC Channel0 selected
+* - ADC_Channel_1: ADC Channel1 selected
+* - ADC_Channel_2: ADC Channel2 selected
+* - ADC_Channel_3: ADC Channel3 selected
+* - ADC_Channel_4: ADC Channel4 selected
+* - ADC_Channel_5: ADC Channel5 selected
+* - ADC_Channel_6: ADC Channel6 selected
+* - ADC_Channel_7: ADC Channel7 selected
+* - ADC_Channel_8: ADC Channel8 selected
+* - ADC_Channel_9: ADC Channel9 selected
+* - ADC_Channel_10: ADC Channel10 selected
+* - ADC_Channel_11: ADC Channel11 selected
+* - ADC_Channel_12: ADC Channel12 selected
+* - ADC_Channel_13: ADC Channel13 selected
+* - ADC_Channel_14: ADC Channel14 selected
+* - ADC_Channel_15: ADC Channel15 selected
+* - ADC_Channel_16: ADC Channel16 selected
+* - ADC_Channel_17: ADC Channel17 selected
+* - Rank: The rank in the injected group sequencer. This parameter
+* must be between 1 to 4.
+* - ADC_SampleTime: The sample time value to be set for the
+* selected channel.
+* This parameter can be one of the following values:
+* - ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles
+* - ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles
+* - ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles
+* - ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles
+* - ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles
+* - ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles
+* - ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles
+* - ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel, u8 Rank, u8 ADC_SampleTime)
+{
+ u32 tmpreg1 = 0, tmpreg2 = 0, tmpreg3 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_CHANNEL(ADC_Channel));
+ assert_param(IS_ADC_INJECTED_RANK(Rank));
+ assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime));
+
+ /* if ADC_Channel_10 ... ADC_Channel_17 is selected */
+ if (ADC_Channel > ADC_Channel_9)
+ {
+ /* Get the old register value */
+ tmpreg1 = ADCx->SMPR1;
+ /* Calculate the mask to clear */
+ tmpreg2 = SMPR1_SMP_Set << (3*(ADC_Channel - 10));
+ /* Clear the old discontinuous mode channel count */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set */
+ tmpreg2 = (u32)ADC_SampleTime << (3*(ADC_Channel - 10));
+ /* Set the discontinuous mode channel count */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->SMPR1 = tmpreg1;
+ }
+ else /* ADC_Channel include in ADC_Channel_[0..9] */
+ {
+ /* Get the old register value */
+ tmpreg1 = ADCx->SMPR2;
+ /* Calculate the mask to clear */
+ tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel);
+ /* Clear the old discontinuous mode channel count */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set */
+ tmpreg2 = (u32)ADC_SampleTime << (3 * ADC_Channel);
+ /* Set the discontinuous mode channel count */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->SMPR2 = tmpreg1;
+ }
+
+ /* Rank configuration */
+ /* Get the old register value */
+ tmpreg1 = ADCx->JSQR;
+ /* Get JL value: Number = JL+1 */
+ tmpreg3 = (tmpreg1 & JSQR_JL_Set)>> 20;
+ /* Calculate the mask to clear: ((Rank-1)+(4-JL-1)) */
+ tmpreg2 = JSQR_JSQ_Set << (5 * (u8)((Rank + 3) - (tmpreg3 + 1)));
+ /* Clear the old JSQx bits for the selected rank */
+ tmpreg1 &= ~tmpreg2;
+ /* Calculate the mask to set: ((Rank-1)+(4-JL-1)) */
+ tmpreg2 = (u32)ADC_Channel << (5 * (u8)((Rank + 3) - (tmpreg3 + 1)));
+ /* Set the JSQx bits for the selected rank */
+ tmpreg1 |= tmpreg2;
+ /* Store the new register value */
+ ADCx->JSQR = tmpreg1;
+}
+
+/*******************************************************************************
+* Function Name : ADC_InjectedSequencerLengthConfig
+* Description : Configures the sequencer length for injected channels
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - Length: The sequencer length.
+* This parameter must be a number between 1 to 4.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, u8 Length)
+{
+ u32 tmpreg1 = 0;
+ u32 tmpreg2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_INJECTED_LENGTH(Length));
+
+ /* Get the old register value */
+ tmpreg1 = ADCx->JSQR;
+ /* Clear the old injected sequnence lenght JL bits */
+ tmpreg1 &= JSQR_JL_Reset;
+ /* Set the injected sequnence lenght JL bits */
+ tmpreg2 = Length - 1;
+ tmpreg1 |= tmpreg2 << 20;
+ /* Store the new register value */
+ ADCx->JSQR = tmpreg1;
+}
+
+/*******************************************************************************
+* Function Name : ADC_SetInjectedOffset
+* Description : Set the injected channels conversion value offset
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_InjectedChannel: the ADC injected channel to set its
+* offset.
+* This parameter can be one of the following values:
+* - ADC_InjectedChannel_1: Injected Channel1 selected
+* - ADC_InjectedChannel_2: Injected Channel2 selected
+* - ADC_InjectedChannel_3: Injected Channel3 selected
+* - ADC_InjectedChannel_4: Injected Channel4 selected
+* - Offset: the offset value for the selected ADC injected channel
+* This parameter must be a 12bit value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, u8 ADC_InjectedChannel, u16 Offset)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel));
+ assert_param(IS_ADC_OFFSET(Offset));
+
+ /* Set the selected injected channel data offset */
+ *((vu32 *)((*(u32*)&ADCx) + ADC_InjectedChannel)) = (u32)Offset;
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetInjectedConversionValue
+* Description : Returns the ADC injected channel conversion result
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_InjectedChannel: the converted ADC injected channel.
+* This parameter can be one of the following values:
+* - ADC_InjectedChannel_1: Injected Channel1 selected
+* - ADC_InjectedChannel_2: Injected Channel2 selected
+* - ADC_InjectedChannel_3: Injected Channel3 selected
+* - ADC_InjectedChannel_4: Injected Channel4 selected
+* Output : None
+* Return : The Data conversion value.
+*******************************************************************************/
+u16 ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, u8 ADC_InjectedChannel)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel));
+
+ /* Returns the selected injected channel conversion data value */
+ return (u16) (*(vu32*) (((*(u32*)&ADCx) + ADC_InjectedChannel + JDR_Offset)));
+}
+
+/*******************************************************************************
+* Function Name : ADC_AnalogWatchdogCmd
+* Description : Enables or disables the analog watchdog on single/all regular
+* or injected channels
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_AnalogWatchdog: the ADC analog watchdog configuration.
+* This parameter can be one of the following values:
+* - ADC_AnalogWatchdog_SingleRegEnable: Analog watchdog on
+* a single regular channel
+* - ADC_AnalogWatchdog_SingleInjecEnable: Analog watchdog on
+* a single injected channel
+* - ADC_AnalogWatchdog_SingleRegOrInjecEnable: Analog
+* watchdog on a single regular or injected channel
+* - ADC_AnalogWatchdog_AllRegEnable: Analog watchdog on
+* all regular channel
+* - ADC_AnalogWatchdog_AllInjecEnable: Analog watchdog on
+* all injected channel
+* - ADC_AnalogWatchdog_AllRegAllInjecEnable: Analog watchdog
+* on all regular and injected channels
+* - ADC_AnalogWatchdog_None: No channel guarded by the
+* analog watchdog
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, u32 ADC_AnalogWatchdog)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_ANALOG_WATCHDOG(ADC_AnalogWatchdog));
+
+ /* Get the old register value */
+ tmpreg = ADCx->CR1;
+ /* Clear AWDEN, AWDENJ and AWDSGL bits */
+ tmpreg &= CR1_AWDMode_Reset;
+ /* Set the analog watchdog enable mode */
+ tmpreg |= ADC_AnalogWatchdog;
+ /* Store the new register value */
+ ADCx->CR1 = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : ADC_AnalogWatchdogThresholdsConfig
+* Description : Configures the high and low thresholds of the analog watchdog.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - HighThreshold: the ADC analog watchdog High threshold value.
+* This parameter must be a 12bit value.
+* - LowThreshold: the ADC analog watchdog Low threshold value.
+* This parameter must be a 12bit value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, u16 HighThreshold,
+ u16 LowThreshold)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_THRESHOLD(HighThreshold));
+ assert_param(IS_ADC_THRESHOLD(LowThreshold));
+
+ /* Set the ADCx high threshold */
+ ADCx->HTR = HighThreshold;
+ /* Set the ADCx low threshold */
+ ADCx->LTR = LowThreshold;
+}
+
+/*******************************************************************************
+* Function Name : ADC_AnalogWatchdogSingleChannelConfig
+* Description : Configures the analog watchdog guarded single channel
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_Channel: the ADC channel to configure for the analog
+* watchdog.
+* This parameter can be one of the following values:
+* - ADC_Channel_0: ADC Channel0 selected
+* - ADC_Channel_1: ADC Channel1 selected
+* - ADC_Channel_2: ADC Channel2 selected
+* - ADC_Channel_3: ADC Channel3 selected
+* - ADC_Channel_4: ADC Channel4 selected
+* - ADC_Channel_5: ADC Channel5 selected
+* - ADC_Channel_6: ADC Channel6 selected
+* - ADC_Channel_7: ADC Channel7 selected
+* - ADC_Channel_8: ADC Channel8 selected
+* - ADC_Channel_9: ADC Channel9 selected
+* - ADC_Channel_10: ADC Channel10 selected
+* - ADC_Channel_11: ADC Channel11 selected
+* - ADC_Channel_12: ADC Channel12 selected
+* - ADC_Channel_13: ADC Channel13 selected
+* - ADC_Channel_14: ADC Channel14 selected
+* - ADC_Channel_15: ADC Channel15 selected
+* - ADC_Channel_16: ADC Channel16 selected
+* - ADC_Channel_17: ADC Channel17 selected
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_CHANNEL(ADC_Channel));
+
+ /* Get the old register value */
+ tmpreg = ADCx->CR1;
+ /* Clear the Analog watchdog channel select bits */
+ tmpreg &= CR1_AWDCH_Reset;
+ /* Set the Analog watchdog channel */
+ tmpreg |= ADC_Channel;
+ /* Store the new register value */
+ ADCx->CR1 = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : ADC_TempSensorVrefintCmd
+* Description : Enables or disables the temperature sensor and Vrefint channel.
+* Input : - NewState: new state of the temperature sensor.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_TempSensorVrefintCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the temperature sensor and Vrefint channel*/
+ ADC1->CR2 |= CR2_TSVREFE_Set;
+ }
+ else
+ {
+ /* Disable the temperature sensor and Vrefint channel*/
+ ADC1->CR2 &= CR2_TSVREFE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetFlagStatus
+* Description : Checks whether the specified ADC flag is set or not.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - ADC_FLAG_AWD: Analog watchdog flag
+* - ADC_FLAG_EOC: End of conversion flag
+* - ADC_FLAG_JEOC: End of injected group conversion flag
+* - ADC_FLAG_JSTRT: Start of injected group conversion flag
+* - ADC_FLAG_STRT: Start of regular group conversion flag
+* Output : None
+* Return : The new state of ADC_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, u8 ADC_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_GET_FLAG(ADC_FLAG));
+
+ /* Check the status of the specified ADC flag */
+ if ((ADCx->SR & ADC_FLAG) != (u8)RESET)
+ {
+ /* ADC_FLAG is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* ADC_FLAG is reset */
+ bitstatus = RESET;
+ }
+
+ /* Return the ADC_FLAG status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : ADC_ClearFlag
+* Description : Clears the ADCx's pending flags.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_FLAG: specifies the flag to clear.
+* This parameter can be any combination of the following values:
+* - ADC_FLAG_AWD: Analog watchdog flag
+* - ADC_FLAG_EOC: End of conversion flag
+* - ADC_FLAG_JEOC: End of injected group conversion flag
+* - ADC_FLAG_JSTRT: Start of injected group conversion flag
+* - ADC_FLAG_STRT: Start of regular group conversion flag
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_ClearFlag(ADC_TypeDef* ADCx, u8 ADC_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_CLEAR_FLAG(ADC_FLAG));
+
+ /* Clear the selected ADC flags */
+ ADCx->SR = ~(u32)ADC_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : ADC_GetITStatus
+* Description : Checks whether the specified ADC interrupt has occurred or not.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_IT: specifies the ADC interrupt source to check.
+* This parameter can be one of the following values:
+* - ADC_IT_EOC: End of conversion interrupt mask
+* - ADC_IT_AWD: Analog watchdog interrupt mask
+* - ADC_IT_JEOC: End of injected conversion interrupt mask
+* Output : None
+* Return : The new state of ADC_IT (SET or RESET).
+*******************************************************************************/
+ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, u16 ADC_IT)
+{
+ ITStatus bitstatus = RESET;
+ u32 itmask = 0, enablestatus = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_GET_IT(ADC_IT));
+
+ /* Get the ADC IT index */
+ itmask = ADC_IT >> 8;
+
+ /* Get the ADC_IT enable bit status */
+ enablestatus = (ADCx->CR1 & (u8)ADC_IT) ;
+
+ /* Check the status of the specified ADC interrupt */
+ if (((ADCx->SR & itmask) != (u32)RESET) && enablestatus)
+ {
+ /* ADC_IT is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* ADC_IT is reset */
+ bitstatus = RESET;
+ }
+
+ /* Return the ADC_IT status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : ADC_ClearITPendingBit
+* Description : Clears the ADCx’s interrupt pending bits.
+* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+* - ADC_IT: specifies the ADC interrupt pending bit to clear.
+* This parameter can be any combination of the following values:
+* - ADC_IT_EOC: End of conversion interrupt mask
+* - ADC_IT_AWD: Analog watchdog interrupt mask
+* - ADC_IT_JEOC: End of injected conversion interrupt mask
+* Output : None
+* Return : None
+*******************************************************************************/
+void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, u16 ADC_IT)
+{
+ u8 itmask = 0;
+
+ /* Check the parameters */
+ assert_param(IS_ADC_ALL_PERIPH(ADCx));
+ assert_param(IS_ADC_IT(ADC_IT));
+
+ /* Get the ADC IT index */
+ itmask = (u8)(ADC_IT >> 8);
+
+ /* Clear the selected ADC interrupt pending bits */
+ ADCx->SR = ~(u32)itmask;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_adc.lst b/src/stm32lib/src/stm32f10x_adc.lst new file mode 100644 index 0000000..ef1caab --- /dev/null +++ b/src/stm32lib/src/stm32f10x_adc.lst @@ -0,0 +1,2584 @@ + 1 .syntax unified + 2 .cpu cortex-m3 + 3 .fpu softvfp + 4 .eabi_attribute 20, 1 + 5 .eabi_attribute 21, 1 + 6 .eabi_attribute 23, 3 + 7 .eabi_attribute 24, 1 + 8 .eabi_attribute 25, 1 + 9 .eabi_attribute 26, 1 + 10 .eabi_attribute 30, 4 + 11 .eabi_attribute 18, 4 + 12 .thumb + 13 .file "stm32f10x_adc.c" + 21 .Ltext0: + 22 .align 2 + 23 .global ADC_Init + 24 .thumb + 25 .thumb_func + 27 ADC_Init: + 28 .LFB24: + 29 .file 1 "stm32lib/src/stm32f10x_adc.c" + 1:stm32lib/src/stm32f10x_adc.c **** /******************** (C) COPYRIGHT 2008 STMicroelectronics ******************** + 2:stm32lib/src/stm32f10x_adc.c **** * File Name : stm32f10x_adc.c + 3:stm32lib/src/stm32f10x_adc.c **** * Author : MCD Application Team + 4:stm32lib/src/stm32f10x_adc.c **** * Version : V2.0.2 + 5:stm32lib/src/stm32f10x_adc.c **** * Date : 07/11/2008 + 6:stm32lib/src/stm32f10x_adc.c **** * Description : This file provides all the ADC firmware functions. + 7:stm32lib/src/stm32f10x_adc.c **** ******************************************************************************** + 8:stm32lib/src/stm32f10x_adc.c **** * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + 9:stm32lib/src/stm32f10x_adc.c **** * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. + 10:stm32lib/src/stm32f10x_adc.c **** * AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, + 11:stm32lib/src/stm32f10x_adc.c **** * INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE + 12:stm32lib/src/stm32f10x_adc.c **** * CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING + 13:stm32lib/src/stm32f10x_adc.c **** * INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + 14:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 15:stm32lib/src/stm32f10x_adc.c **** + 16:stm32lib/src/stm32f10x_adc.c **** /* Includes ------------------------------------------------------------------*/ + 17:stm32lib/src/stm32f10x_adc.c **** #include "stm32f10x_adc.h" + 18:stm32lib/src/stm32f10x_adc.c **** #include "stm32f10x_rcc.h" + 19:stm32lib/src/stm32f10x_adc.c **** + 20:stm32lib/src/stm32f10x_adc.c **** /* Private typedef -----------------------------------------------------------*/ + 21:stm32lib/src/stm32f10x_adc.c **** /* Private define ------------------------------------------------------------*/ + 22:stm32lib/src/stm32f10x_adc.c **** /* ADC DISCNUM mask */ + 23:stm32lib/src/stm32f10x_adc.c **** #define CR1_DISCNUM_Reset ((u32)0xFFFF1FFF) + 24:stm32lib/src/stm32f10x_adc.c **** + 25:stm32lib/src/stm32f10x_adc.c **** /* ADC DISCEN mask */ + 26:stm32lib/src/stm32f10x_adc.c **** #define CR1_DISCEN_Set ((u32)0x00000800) + 27:stm32lib/src/stm32f10x_adc.c **** #define CR1_DISCEN_Reset ((u32)0xFFFFF7FF) + 28:stm32lib/src/stm32f10x_adc.c **** + 29:stm32lib/src/stm32f10x_adc.c **** /* ADC JAUTO mask */ + 30:stm32lib/src/stm32f10x_adc.c **** #define CR1_JAUTO_Set ((u32)0x00000400) + 31:stm32lib/src/stm32f10x_adc.c **** #define CR1_JAUTO_Reset ((u32)0xFFFFFBFF) + 32:stm32lib/src/stm32f10x_adc.c **** + 33:stm32lib/src/stm32f10x_adc.c **** /* ADC JDISCEN mask */ + 34:stm32lib/src/stm32f10x_adc.c **** #define CR1_JDISCEN_Set ((u32)0x00001000) + 35:stm32lib/src/stm32f10x_adc.c **** #define CR1_JDISCEN_Reset ((u32)0xFFFFEFFF) + 36:stm32lib/src/stm32f10x_adc.c **** + 37:stm32lib/src/stm32f10x_adc.c **** /* ADC AWDCH mask */ + 38:stm32lib/src/stm32f10x_adc.c **** #define CR1_AWDCH_Reset ((u32)0xFFFFFFE0) + 39:stm32lib/src/stm32f10x_adc.c **** + 40:stm32lib/src/stm32f10x_adc.c **** /* ADC Analog watchdog enable mode mask */ + 41:stm32lib/src/stm32f10x_adc.c **** #define CR1_AWDMode_Reset ((u32)0xFF3FFDFF) + 42:stm32lib/src/stm32f10x_adc.c **** + 43:stm32lib/src/stm32f10x_adc.c **** /* CR1 register Mask */ + 44:stm32lib/src/stm32f10x_adc.c **** #define CR1_CLEAR_Mask ((u32)0xFFF0FEFF) + 45:stm32lib/src/stm32f10x_adc.c **** + 46:stm32lib/src/stm32f10x_adc.c **** /* ADC ADON mask */ + 47:stm32lib/src/stm32f10x_adc.c **** #define CR2_ADON_Set ((u32)0x00000001) + 48:stm32lib/src/stm32f10x_adc.c **** #define CR2_ADON_Reset ((u32)0xFFFFFFFE) + 49:stm32lib/src/stm32f10x_adc.c **** + 50:stm32lib/src/stm32f10x_adc.c **** /* ADC DMA mask */ + 51:stm32lib/src/stm32f10x_adc.c **** #define CR2_DMA_Set ((u32)0x00000100) + 52:stm32lib/src/stm32f10x_adc.c **** #define CR2_DMA_Reset ((u32)0xFFFFFEFF) + 53:stm32lib/src/stm32f10x_adc.c **** + 54:stm32lib/src/stm32f10x_adc.c **** /* ADC RSTCAL mask */ + 55:stm32lib/src/stm32f10x_adc.c **** #define CR2_RSTCAL_Set ((u32)0x00000008) + 56:stm32lib/src/stm32f10x_adc.c **** + 57:stm32lib/src/stm32f10x_adc.c **** /* ADC CAL mask */ + 58:stm32lib/src/stm32f10x_adc.c **** #define CR2_CAL_Set ((u32)0x00000004) + 59:stm32lib/src/stm32f10x_adc.c **** + 60:stm32lib/src/stm32f10x_adc.c **** /* ADC SWSTART mask */ + 61:stm32lib/src/stm32f10x_adc.c **** #define CR2_SWSTART_Set ((u32)0x00400000) + 62:stm32lib/src/stm32f10x_adc.c **** + 63:stm32lib/src/stm32f10x_adc.c **** /* ADC EXTTRIG mask */ + 64:stm32lib/src/stm32f10x_adc.c **** #define CR2_EXTTRIG_Set ((u32)0x00100000) + 65:stm32lib/src/stm32f10x_adc.c **** #define CR2_EXTTRIG_Reset ((u32)0xFFEFFFFF) + 66:stm32lib/src/stm32f10x_adc.c **** + 67:stm32lib/src/stm32f10x_adc.c **** /* ADC Software start mask */ + 68:stm32lib/src/stm32f10x_adc.c **** #define CR2_EXTTRIG_SWSTART_Set ((u32)0x00500000) + 69:stm32lib/src/stm32f10x_adc.c **** #define CR2_EXTTRIG_SWSTART_Reset ((u32)0xFFAFFFFF) + 70:stm32lib/src/stm32f10x_adc.c **** + 71:stm32lib/src/stm32f10x_adc.c **** /* ADC JEXTSEL mask */ + 72:stm32lib/src/stm32f10x_adc.c **** #define CR2_JEXTSEL_Reset ((u32)0xFFFF8FFF) + 73:stm32lib/src/stm32f10x_adc.c **** + 74:stm32lib/src/stm32f10x_adc.c **** /* ADC JEXTTRIG mask */ + 75:stm32lib/src/stm32f10x_adc.c **** #define CR2_JEXTTRIG_Set ((u32)0x00008000) + 76:stm32lib/src/stm32f10x_adc.c **** #define CR2_JEXTTRIG_Reset ((u32)0xFFFF7FFF) + 77:stm32lib/src/stm32f10x_adc.c **** + 78:stm32lib/src/stm32f10x_adc.c **** /* ADC JSWSTART mask */ + 79:stm32lib/src/stm32f10x_adc.c **** #define CR2_JSWSTART_Set ((u32)0x00200000) + 80:stm32lib/src/stm32f10x_adc.c **** + 81:stm32lib/src/stm32f10x_adc.c **** /* ADC injected software start mask */ + 82:stm32lib/src/stm32f10x_adc.c **** #define CR2_JEXTTRIG_JSWSTART_Set ((u32)0x00208000) + 83:stm32lib/src/stm32f10x_adc.c **** #define CR2_JEXTTRIG_JSWSTART_Reset ((u32)0xFFDF7FFF) + 84:stm32lib/src/stm32f10x_adc.c **** + 85:stm32lib/src/stm32f10x_adc.c **** /* ADC TSPD mask */ + 86:stm32lib/src/stm32f10x_adc.c **** #define CR2_TSVREFE_Set ((u32)0x00800000) + 87:stm32lib/src/stm32f10x_adc.c **** #define CR2_TSVREFE_Reset ((u32)0xFF7FFFFF) + 88:stm32lib/src/stm32f10x_adc.c **** + 89:stm32lib/src/stm32f10x_adc.c **** /* CR2 register Mask */ + 90:stm32lib/src/stm32f10x_adc.c **** #define CR2_CLEAR_Mask ((u32)0xFFF1F7FD) + 91:stm32lib/src/stm32f10x_adc.c **** + 92:stm32lib/src/stm32f10x_adc.c **** /* ADC SQx mask */ + 93:stm32lib/src/stm32f10x_adc.c **** #define SQR3_SQ_Set ((u32)0x0000001F) + 94:stm32lib/src/stm32f10x_adc.c **** #define SQR2_SQ_Set ((u32)0x0000001F) + 95:stm32lib/src/stm32f10x_adc.c **** #define SQR1_SQ_Set ((u32)0x0000001F) + 96:stm32lib/src/stm32f10x_adc.c **** + 97:stm32lib/src/stm32f10x_adc.c **** /* SQR1 register Mask */ + 98:stm32lib/src/stm32f10x_adc.c **** #define SQR1_CLEAR_Mask ((u32)0xFF0FFFFF) + 99:stm32lib/src/stm32f10x_adc.c **** + 100:stm32lib/src/stm32f10x_adc.c **** /* ADC JSQx mask */ + 101:stm32lib/src/stm32f10x_adc.c **** #define JSQR_JSQ_Set ((u32)0x0000001F) + 102:stm32lib/src/stm32f10x_adc.c **** + 103:stm32lib/src/stm32f10x_adc.c **** /* ADC JL mask */ + 104:stm32lib/src/stm32f10x_adc.c **** #define JSQR_JL_Set ((u32)0x00300000) + 105:stm32lib/src/stm32f10x_adc.c **** #define JSQR_JL_Reset ((u32)0xFFCFFFFF) + 106:stm32lib/src/stm32f10x_adc.c **** + 107:stm32lib/src/stm32f10x_adc.c **** /* ADC SMPx mask */ + 108:stm32lib/src/stm32f10x_adc.c **** #define SMPR1_SMP_Set ((u32)0x00000007) + 109:stm32lib/src/stm32f10x_adc.c **** #define SMPR2_SMP_Set ((u32)0x00000007) + 110:stm32lib/src/stm32f10x_adc.c **** + 111:stm32lib/src/stm32f10x_adc.c **** /* ADC JDRx registers offset */ + 112:stm32lib/src/stm32f10x_adc.c **** #define JDR_Offset ((u8)0x28) + 113:stm32lib/src/stm32f10x_adc.c **** + 114:stm32lib/src/stm32f10x_adc.c **** /* ADC1 DR register base address */ + 115:stm32lib/src/stm32f10x_adc.c **** #define DR_ADDRESS ((u32)0x4001244C) + 116:stm32lib/src/stm32f10x_adc.c **** + 117:stm32lib/src/stm32f10x_adc.c **** /* Private macro -------------------------------------------------------------*/ + 118:stm32lib/src/stm32f10x_adc.c **** /* Private variables ---------------------------------------------------------*/ + 119:stm32lib/src/stm32f10x_adc.c **** /* Private function prototypes -----------------------------------------------*/ + 120:stm32lib/src/stm32f10x_adc.c **** /* Private functions ---------------------------------------------------------*/ + 121:stm32lib/src/stm32f10x_adc.c **** + 122:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 123:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_DeInit + 124:stm32lib/src/stm32f10x_adc.c **** * Description : Deinitializes the ADCx peripheral registers to their default + 125:stm32lib/src/stm32f10x_adc.c **** * reset values. + 126:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 127:stm32lib/src/stm32f10x_adc.c **** * Output : None + 128:stm32lib/src/stm32f10x_adc.c **** * Return : None + 129:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 130:stm32lib/src/stm32f10x_adc.c **** void ADC_DeInit(ADC_TypeDef* ADCx) + 131:stm32lib/src/stm32f10x_adc.c **** { + 132:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 133:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 134:stm32lib/src/stm32f10x_adc.c **** + 135:stm32lib/src/stm32f10x_adc.c **** switch (*(u32*)&ADCx) + 136:stm32lib/src/stm32f10x_adc.c **** { + 137:stm32lib/src/stm32f10x_adc.c **** case ADC1_BASE: + 138:stm32lib/src/stm32f10x_adc.c **** /* Enable ADC1 reset state */ + 139:stm32lib/src/stm32f10x_adc.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, ENABLE); + 140:stm32lib/src/stm32f10x_adc.c **** /* Release ADC1 from reset state */ + 141:stm32lib/src/stm32f10x_adc.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, DISABLE); + 142:stm32lib/src/stm32f10x_adc.c **** break; + 143:stm32lib/src/stm32f10x_adc.c **** + 144:stm32lib/src/stm32f10x_adc.c **** case ADC2_BASE: + 145:stm32lib/src/stm32f10x_adc.c **** /* Enable ADC2 reset state */ + 146:stm32lib/src/stm32f10x_adc.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, ENABLE); + 147:stm32lib/src/stm32f10x_adc.c **** /* Release ADC2 from reset state */ + 148:stm32lib/src/stm32f10x_adc.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, DISABLE); + 149:stm32lib/src/stm32f10x_adc.c **** break; + 150:stm32lib/src/stm32f10x_adc.c **** + 151:stm32lib/src/stm32f10x_adc.c **** case ADC3_BASE: + 152:stm32lib/src/stm32f10x_adc.c **** /* Enable ADC3 reset state */ + 153:stm32lib/src/stm32f10x_adc.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, ENABLE); + 154:stm32lib/src/stm32f10x_adc.c **** /* Release ADC3 from reset state */ + 155:stm32lib/src/stm32f10x_adc.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, DISABLE); + 156:stm32lib/src/stm32f10x_adc.c **** break; + 157:stm32lib/src/stm32f10x_adc.c **** + 158:stm32lib/src/stm32f10x_adc.c **** default: + 159:stm32lib/src/stm32f10x_adc.c **** break; + 160:stm32lib/src/stm32f10x_adc.c **** } + 161:stm32lib/src/stm32f10x_adc.c **** } + 162:stm32lib/src/stm32f10x_adc.c **** + 163:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 164:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_Init + 165:stm32lib/src/stm32f10x_adc.c **** * Description : Initializes the ADCx peripheral according to the specified parameters + 166:stm32lib/src/stm32f10x_adc.c **** * in the ADC_InitStruct. + 167:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 168:stm32lib/src/stm32f10x_adc.c **** * - ADC_InitStruct: pointer to an ADC_InitTypeDef structure that + 169:stm32lib/src/stm32f10x_adc.c **** * contains the configuration information for the specified + 170:stm32lib/src/stm32f10x_adc.c **** * ADC peripheral. + 171:stm32lib/src/stm32f10x_adc.c **** * Output : None + 172:stm32lib/src/stm32f10x_adc.c **** * Return : None + 173:stm32lib/src/stm32f10x_adc.c **** ******************************************************************************/ + 174:stm32lib/src/stm32f10x_adc.c **** void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct) + 175:stm32lib/src/stm32f10x_adc.c **** { + 30 .loc 1 175 0 + 31 @ args = 0, pretend = 0, frame = 0 + 32 @ frame_needed = 0, uses_anonymous_args = 0 + 33 .LVL0: + 176:stm32lib/src/stm32f10x_adc.c **** u32 tmpreg1 = 0; + 177:stm32lib/src/stm32f10x_adc.c **** u8 tmpreg2 = 0; + 178:stm32lib/src/stm32f10x_adc.c **** + 179:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 180:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 181:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_MODE(ADC_InitStruct->ADC_Mode)); + 182:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ScanConvMode)); + 183:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ContinuousConvMode)); + 184:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_EXT_TRIG(ADC_InitStruct->ADC_ExternalTrigConv)); + 185:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_DATA_ALIGN(ADC_InitStruct->ADC_DataAlign)); + 186:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_REGULAR_LENGTH(ADC_InitStruct->ADC_NbrOfChannel)); + 187:stm32lib/src/stm32f10x_adc.c **** + 188:stm32lib/src/stm32f10x_adc.c **** /*---------------------------- ADCx CR1 Configuration -----------------*/ + 189:stm32lib/src/stm32f10x_adc.c **** /* Get the ADCx CR1 value */ + 190:stm32lib/src/stm32f10x_adc.c **** tmpreg1 = ADCx->CR1; + 34 .loc 1 190 0 + 35 0000 4368 ldr r3, [r0, #4] + 36 .LVL1: + 191:stm32lib/src/stm32f10x_adc.c **** /* Clear DUALMOD and SCAN bits */ + 192:stm32lib/src/stm32f10x_adc.c **** tmpreg1 &= CR1_CLEAR_Mask; + 193:stm32lib/src/stm32f10x_adc.c **** /* Configure ADCx: Dual mode and scan conversion mode */ + 194:stm32lib/src/stm32f10x_adc.c **** /* Set DUALMOD bits according to ADC_Mode value */ + 195:stm32lib/src/stm32f10x_adc.c **** /* Set SCAN bit according to ADC_ScanConvMode value */ + 196:stm32lib/src/stm32f10x_adc.c **** tmpreg1 |= (u32)(ADC_InitStruct->ADC_Mode | ((u32)ADC_InitStruct->ADC_ScanConvMode << 8)); + 37 .loc 1 196 0 + 38 0002 0A68 ldr r2, [r1, #0] + 39 0004 23F47023 bic r3, r3, #983040 + 40 .LVL2: + 41 0008 23F48073 bic r3, r3, #256 + 42 000c 1343 orrs r3, r3, r2 + 43 000e 0A79 ldrb r2, [r1, #4] @ zero_extendqisi2 + 44 .loc 1 175 0 + 45 0010 10B5 push {r4, lr} + 46 .LCFI0: + 47 .loc 1 196 0 + 48 0012 43EA0223 orr r3, r3, r2, lsl #8 + 49 .LVL3: + 197:stm32lib/src/stm32f10x_adc.c **** /* Write to ADCx CR1 */ + 198:stm32lib/src/stm32f10x_adc.c **** ADCx->CR1 = tmpreg1; + 50 .loc 1 198 0 + 51 0016 4360 str r3, [r0, #4] + 199:stm32lib/src/stm32f10x_adc.c **** + 200:stm32lib/src/stm32f10x_adc.c **** /*---------------------------- ADCx CR2 Configuration -----------------*/ + 201:stm32lib/src/stm32f10x_adc.c **** /* Get the ADCx CR2 value */ + 202:stm32lib/src/stm32f10x_adc.c **** tmpreg1 = ADCx->CR2; + 203:stm32lib/src/stm32f10x_adc.c **** /* Clear CONT, ALIGN and EXTSEL bits */ + 204:stm32lib/src/stm32f10x_adc.c **** tmpreg1 &= CR2_CLEAR_Mask; + 205:stm32lib/src/stm32f10x_adc.c **** /* Configure ADCx: external trigger event and continuous conversion mode */ + 206:stm32lib/src/stm32f10x_adc.c **** /* Set ALIGN bit according to ADC_DataAlign value */ + 207:stm32lib/src/stm32f10x_adc.c **** /* Set EXTSEL bits according to ADC_ExternalTrigConv value */ + 208:stm32lib/src/stm32f10x_adc.c **** /* Set CONT bit according to ADC_ContinuousConvMode value */ + 209:stm32lib/src/stm32f10x_adc.c **** tmpreg1 |= (u32)(ADC_InitStruct->ADC_DataAlign | ADC_InitStruct->ADC_ExternalTrigConv | + 52 .loc 1 209 0 + 53 0018 CB68 ldr r3, [r1, #12] + 54 .LVL4: + 55 001a 8A68 ldr r2, [r1, #8] + 56 .loc 1 202 0 + 57 001c 8468 ldr r4, [r0, #8] + 58 .LVL5: + 59 .loc 1 209 0 + 60 001e 1A43 orrs r2, r2, r3 + 61 0020 084B ldr r3, .L3 + 62 0022 04EA0303 and r3, r4, r3 + 63 0026 1A43 orrs r2, r2, r3 + 64 0028 4B79 ldrb r3, [r1, #5] @ zero_extendqisi2 + 65 002a 42EA4302 orr r2, r2, r3, lsl #1 + 66 .LVL6: + 210:stm32lib/src/stm32f10x_adc.c **** ((u32)ADC_InitStruct->ADC_ContinuousConvMode << 1)); + 211:stm32lib/src/stm32f10x_adc.c **** /* Write to ADCx CR2 */ + 212:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 = tmpreg1; + 67 .loc 1 212 0 + 68 002e 8260 str r2, [r0, #8] + 213:stm32lib/src/stm32f10x_adc.c **** + 214:stm32lib/src/stm32f10x_adc.c **** /*---------------------------- ADCx SQR1 Configuration -----------------*/ + 215:stm32lib/src/stm32f10x_adc.c **** /* Get the ADCx SQR1 value */ + 216:stm32lib/src/stm32f10x_adc.c **** tmpreg1 = ADCx->SQR1; + 217:stm32lib/src/stm32f10x_adc.c **** /* Clear L bits */ + 218:stm32lib/src/stm32f10x_adc.c **** tmpreg1 &= SQR1_CLEAR_Mask; + 219:stm32lib/src/stm32f10x_adc.c **** /* Configure ADCx: regular channel sequence length */ + 220:stm32lib/src/stm32f10x_adc.c **** /* Set L bits according to ADC_NbrOfChannel value */ + 221:stm32lib/src/stm32f10x_adc.c **** tmpreg2 |= (ADC_InitStruct->ADC_NbrOfChannel - 1); + 222:stm32lib/src/stm32f10x_adc.c **** tmpreg1 |= ((u32)tmpreg2 << 20); + 69 .loc 1 222 0 + 70 0030 0B7C ldrb r3, [r1, #16] @ zero_extendqisi2 + 71 .loc 1 216 0 + 72 0032 C26A ldr r2, [r0, #44] + 73 .LVL7: + 74 .loc 1 222 0 + 75 0034 013B subs r3, r3, #1 + 76 .loc 1 218 0 + 77 0036 22F47002 bic r2, r2, #15728640 + 78 .LVL8: + 79 .loc 1 222 0 + 80 003a DBB2 uxtb r3, r3 + 81 003c 42EA0352 orr r2, r2, r3, lsl #20 + 82 .LVL9: + 223:stm32lib/src/stm32f10x_adc.c **** /* Write to ADCx SQR1 */ + 224:stm32lib/src/stm32f10x_adc.c **** ADCx->SQR1 = tmpreg1; + 83 .loc 1 224 0 + 84 0040 C262 str r2, [r0, #44] + 225:stm32lib/src/stm32f10x_adc.c **** } + 85 .loc 1 225 0 + 86 0042 10BD pop {r4, pc} + 87 .L4: + 88 .align 2 + 89 .L3: + 90 0044 FDF7F1FF .word -919555 + 91 .LFE24: + 93 .align 2 + 94 .global ADC_StructInit + 95 .thumb + 96 .thumb_func + 98 ADC_StructInit: + 99 .LFB25: + 226:stm32lib/src/stm32f10x_adc.c **** + 227:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 228:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_StructInit + 229:stm32lib/src/stm32f10x_adc.c **** * Description : Fills each ADC_InitStruct member with its default value. + 230:stm32lib/src/stm32f10x_adc.c **** * Input : ADC_InitStruct : pointer to an ADC_InitTypeDef structure + 231:stm32lib/src/stm32f10x_adc.c **** * which will be initialized. + 232:stm32lib/src/stm32f10x_adc.c **** * Output : None + 233:stm32lib/src/stm32f10x_adc.c **** * Return : None + 234:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 235:stm32lib/src/stm32f10x_adc.c **** void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct) + 236:stm32lib/src/stm32f10x_adc.c **** { + 100 .loc 1 236 0 + 101 @ args = 0, pretend = 0, frame = 0 + 102 @ frame_needed = 0, uses_anonymous_args = 0 + 103 @ link register save eliminated. + 104 .LVL10: + 237:stm32lib/src/stm32f10x_adc.c **** /* Reset ADC init structure parameters values */ + 238:stm32lib/src/stm32f10x_adc.c **** /* Initialize the ADC_Mode member */ + 239:stm32lib/src/stm32f10x_adc.c **** ADC_InitStruct->ADC_Mode = ADC_Mode_Independent; + 105 .loc 1 239 0 + 106 0048 0023 movs r3, #0 + 107 004a 0360 str r3, [r0, #0] + 240:stm32lib/src/stm32f10x_adc.c **** + 241:stm32lib/src/stm32f10x_adc.c **** /* initialize the ADC_ScanConvMode member */ + 242:stm32lib/src/stm32f10x_adc.c **** ADC_InitStruct->ADC_ScanConvMode = DISABLE; + 108 .loc 1 242 0 + 109 004c 0371 strb r3, [r0, #4] + 243:stm32lib/src/stm32f10x_adc.c **** + 244:stm32lib/src/stm32f10x_adc.c **** /* Initialize the ADC_ContinuousConvMode member */ + 245:stm32lib/src/stm32f10x_adc.c **** ADC_InitStruct->ADC_ContinuousConvMode = DISABLE; + 110 .loc 1 245 0 + 111 004e 4371 strb r3, [r0, #5] + 246:stm32lib/src/stm32f10x_adc.c **** + 247:stm32lib/src/stm32f10x_adc.c **** /* Initialize the ADC_ExternalTrigConv member */ + 248:stm32lib/src/stm32f10x_adc.c **** ADC_InitStruct->ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1; + 112 .loc 1 248 0 + 113 0050 8360 str r3, [r0, #8] + 249:stm32lib/src/stm32f10x_adc.c **** + 250:stm32lib/src/stm32f10x_adc.c **** /* Initialize the ADC_DataAlign member */ + 251:stm32lib/src/stm32f10x_adc.c **** ADC_InitStruct->ADC_DataAlign = ADC_DataAlign_Right; + 114 .loc 1 251 0 + 115 0052 C360 str r3, [r0, #12] + 252:stm32lib/src/stm32f10x_adc.c **** + 253:stm32lib/src/stm32f10x_adc.c **** /* Initialize the ADC_NbrOfChannel member */ + 254:stm32lib/src/stm32f10x_adc.c **** ADC_InitStruct->ADC_NbrOfChannel = 1; + 116 .loc 1 254 0 + 117 0054 0133 adds r3, r3, #1 + 118 0056 0374 strb r3, [r0, #16] + 255:stm32lib/src/stm32f10x_adc.c **** } + 119 .loc 1 255 0 + 120 0058 7047 bx lr + 121 .LFE25: + 123 005a 00BF .align 2 + 124 .global ADC_Cmd + 125 .thumb + 126 .thumb_func + 128 ADC_Cmd: + 129 .LFB26: + 256:stm32lib/src/stm32f10x_adc.c **** + 257:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 258:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_Cmd + 259:stm32lib/src/stm32f10x_adc.c **** * Description : Enables or disables the specified ADC peripheral. + 260:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 261:stm32lib/src/stm32f10x_adc.c **** * - NewState: new state of the ADCx peripheral. This parameter + 262:stm32lib/src/stm32f10x_adc.c **** * can be: ENABLE or DISABLE. + 263:stm32lib/src/stm32f10x_adc.c **** * Output : None + 264:stm32lib/src/stm32f10x_adc.c **** * Return : None + 265:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 266:stm32lib/src/stm32f10x_adc.c **** void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState) + 267:stm32lib/src/stm32f10x_adc.c **** { + 130 .loc 1 267 0 + 131 @ args = 0, pretend = 0, frame = 0 + 132 @ frame_needed = 0, uses_anonymous_args = 0 + 133 @ link register save eliminated. + 134 .LVL11: + 268:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 269:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 270:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 271:stm32lib/src/stm32f10x_adc.c **** + 272:stm32lib/src/stm32f10x_adc.c **** if (NewState != DISABLE) + 135 .loc 1 272 0 + 136 005c 19B1 cbz r1, .L8 + 273:stm32lib/src/stm32f10x_adc.c **** { + 274:stm32lib/src/stm32f10x_adc.c **** /* Set the ADON bit to wake up the ADC from power down mode */ + 275:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 |= CR2_ADON_Set; + 137 .loc 1 275 0 + 138 005e 8368 ldr r3, [r0, #8] + 139 0060 43F00103 orr r3, r3, #1 + 140 0064 02E0 b .L11 + 141 .L8: + 276:stm32lib/src/stm32f10x_adc.c **** } + 277:stm32lib/src/stm32f10x_adc.c **** else + 278:stm32lib/src/stm32f10x_adc.c **** { + 279:stm32lib/src/stm32f10x_adc.c **** /* Disable the selected ADC peripheral */ + 280:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 &= CR2_ADON_Reset; + 142 .loc 1 280 0 + 143 0066 8368 ldr r3, [r0, #8] + 144 0068 23F00103 bic r3, r3, #1 + 145 .L11: + 146 006c 8360 str r3, [r0, #8] + 281:stm32lib/src/stm32f10x_adc.c **** } + 282:stm32lib/src/stm32f10x_adc.c **** } + 147 .loc 1 282 0 + 148 006e 7047 bx lr + 149 .LFE26: + 151 .align 2 + 152 .global ADC_DMACmd + 153 .thumb + 154 .thumb_func + 156 ADC_DMACmd: + 157 .LFB27: + 283:stm32lib/src/stm32f10x_adc.c **** + 284:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 285:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_DMACmd + 286:stm32lib/src/stm32f10x_adc.c **** * Description : Enables or disables the specified ADC DMA request. + 287:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1 or 3 to select the ADC peripheral. + 288:stm32lib/src/stm32f10x_adc.c **** * Note: ADC2 hasn't a DMA capability. + 289:stm32lib/src/stm32f10x_adc.c **** * - NewState: new state of the selected ADC DMA transfer. + 290:stm32lib/src/stm32f10x_adc.c **** * This parameter can be: ENABLE or DISABLE. + 291:stm32lib/src/stm32f10x_adc.c **** * Output : None + 292:stm32lib/src/stm32f10x_adc.c **** * Return : None + 293:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 294:stm32lib/src/stm32f10x_adc.c **** void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState) + 295:stm32lib/src/stm32f10x_adc.c **** { + 158 .loc 1 295 0 + 159 @ args = 0, pretend = 0, frame = 0 + 160 @ frame_needed = 0, uses_anonymous_args = 0 + 161 @ link register save eliminated. + 162 .LVL12: + 296:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 297:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_DMA_PERIPH(ADCx)); + 298:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 299:stm32lib/src/stm32f10x_adc.c **** + 300:stm32lib/src/stm32f10x_adc.c **** if (NewState != DISABLE) + 163 .loc 1 300 0 + 164 0070 19B1 cbz r1, .L13 + 301:stm32lib/src/stm32f10x_adc.c **** { + 302:stm32lib/src/stm32f10x_adc.c **** /* Enable the selected ADC DMA request */ + 303:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 |= CR2_DMA_Set; + 165 .loc 1 303 0 + 166 0072 8368 ldr r3, [r0, #8] + 167 0074 43F48073 orr r3, r3, #256 + 168 0078 02E0 b .L16 + 169 .L13: + 304:stm32lib/src/stm32f10x_adc.c **** } + 305:stm32lib/src/stm32f10x_adc.c **** else + 306:stm32lib/src/stm32f10x_adc.c **** { + 307:stm32lib/src/stm32f10x_adc.c **** /* Disable the selected ADC DMA request */ + 308:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 &= CR2_DMA_Reset; + 170 .loc 1 308 0 + 171 007a 8368 ldr r3, [r0, #8] + 172 007c 23F48073 bic r3, r3, #256 + 173 .L16: + 174 0080 8360 str r3, [r0, #8] + 309:stm32lib/src/stm32f10x_adc.c **** } + 310:stm32lib/src/stm32f10x_adc.c **** } + 175 .loc 1 310 0 + 176 0082 7047 bx lr + 177 .LFE27: + 179 .align 2 + 180 .global ADC_ITConfig + 181 .thumb + 182 .thumb_func + 184 ADC_ITConfig: + 185 .LFB28: + 311:stm32lib/src/stm32f10x_adc.c **** + 312:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 313:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_ITConfig + 314:stm32lib/src/stm32f10x_adc.c **** * Description : Enables or disables the specified ADC interrupts. + 315:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 316:stm32lib/src/stm32f10x_adc.c **** * - ADC_IT: specifies the ADC interrupt sources to be enabled + 317:stm32lib/src/stm32f10x_adc.c **** * or disabled. + 318:stm32lib/src/stm32f10x_adc.c **** * This parameter can be any combination of the following values: + 319:stm32lib/src/stm32f10x_adc.c **** * - ADC_IT_EOC: End of conversion interrupt mask + 320:stm32lib/src/stm32f10x_adc.c **** * - ADC_IT_AWD: Analog watchdog interrupt mask + 321:stm32lib/src/stm32f10x_adc.c **** * - ADC_IT_JEOC: End of injected conversion interrupt mask + 322:stm32lib/src/stm32f10x_adc.c **** * - NewState: new state of the specified ADC interrupts. + 323:stm32lib/src/stm32f10x_adc.c **** * This parameter can be: ENABLE or DISABLE. + 324:stm32lib/src/stm32f10x_adc.c **** * Output : None + 325:stm32lib/src/stm32f10x_adc.c **** * Return : None + 326:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 327:stm32lib/src/stm32f10x_adc.c **** void ADC_ITConfig(ADC_TypeDef* ADCx, u16 ADC_IT, FunctionalState NewState) + 328:stm32lib/src/stm32f10x_adc.c **** { + 186 .loc 1 328 0 + 187 @ args = 0, pretend = 0, frame = 0 + 188 @ frame_needed = 0, uses_anonymous_args = 0 + 189 @ link register save eliminated. + 190 .LVL13: + 329:stm32lib/src/stm32f10x_adc.c **** u8 itmask = 0; + 330:stm32lib/src/stm32f10x_adc.c **** + 331:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 332:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 333:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 334:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_IT(ADC_IT)); + 335:stm32lib/src/stm32f10x_adc.c **** + 336:stm32lib/src/stm32f10x_adc.c **** /* Get the ADC IT index */ + 337:stm32lib/src/stm32f10x_adc.c **** itmask = (u8)ADC_IT; + 191 .loc 1 337 0 + 192 0084 C9B2 uxtb r1, r1 + 193 .LVL14: + 338:stm32lib/src/stm32f10x_adc.c **** + 339:stm32lib/src/stm32f10x_adc.c **** if (NewState != DISABLE) + 194 .loc 1 339 0 + 195 0086 1AB1 cbz r2, .L18 + 340:stm32lib/src/stm32f10x_adc.c **** { + 341:stm32lib/src/stm32f10x_adc.c **** /* Enable the selected ADC interrupts */ + 342:stm32lib/src/stm32f10x_adc.c **** ADCx->CR1 |= itmask; + 196 .loc 1 342 0 + 197 0088 4368 ldr r3, [r0, #4] + 198 008a 41EA0303 orr r3, r1, r3 + 199 008e 02E0 b .L21 + 200 .L18: + 343:stm32lib/src/stm32f10x_adc.c **** } + 344:stm32lib/src/stm32f10x_adc.c **** else + 345:stm32lib/src/stm32f10x_adc.c **** { + 346:stm32lib/src/stm32f10x_adc.c **** /* Disable the selected ADC interrupts */ + 347:stm32lib/src/stm32f10x_adc.c **** ADCx->CR1 &= (~(u32)itmask); + 201 .loc 1 347 0 + 202 0090 4368 ldr r3, [r0, #4] + 203 0092 23EA0103 bic r3, r3, r1 + 204 .L21: + 205 0096 4360 str r3, [r0, #4] + 348:stm32lib/src/stm32f10x_adc.c **** } + 349:stm32lib/src/stm32f10x_adc.c **** } + 206 .loc 1 349 0 + 207 0098 7047 bx lr + 208 .LFE28: + 210 009a 00BF .align 2 + 211 .global ADC_ResetCalibration + 212 .thumb + 213 .thumb_func + 215 ADC_ResetCalibration: + 216 .LFB29: + 350:stm32lib/src/stm32f10x_adc.c **** + 351:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 352:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_ResetCalibration + 353:stm32lib/src/stm32f10x_adc.c **** * Description : Resets the selected ADC calibration registers. + 354:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 355:stm32lib/src/stm32f10x_adc.c **** * Output : None + 356:stm32lib/src/stm32f10x_adc.c **** * Return : None + 357:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 358:stm32lib/src/stm32f10x_adc.c **** void ADC_ResetCalibration(ADC_TypeDef* ADCx) + 359:stm32lib/src/stm32f10x_adc.c **** { + 217 .loc 1 359 0 + 218 @ args = 0, pretend = 0, frame = 0 + 219 @ frame_needed = 0, uses_anonymous_args = 0 + 220 @ link register save eliminated. + 221 .LVL15: + 360:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 361:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 362:stm32lib/src/stm32f10x_adc.c **** + 363:stm32lib/src/stm32f10x_adc.c **** /* Resets the selected ADC calibartion registers */ + 364:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 |= CR2_RSTCAL_Set; + 222 .loc 1 364 0 + 223 009c 8368 ldr r3, [r0, #8] + 224 009e 43F00803 orr r3, r3, #8 + 225 00a2 8360 str r3, [r0, #8] + 365:stm32lib/src/stm32f10x_adc.c **** } + 226 .loc 1 365 0 + 227 00a4 7047 bx lr + 228 .LFE29: + 230 00a6 00BF .align 2 + 231 .global ADC_GetResetCalibrationStatus + 232 .thumb + 233 .thumb_func + 235 ADC_GetResetCalibrationStatus: + 236 .LFB30: + 366:stm32lib/src/stm32f10x_adc.c **** + 367:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 368:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_GetResetCalibrationStatus + 369:stm32lib/src/stm32f10x_adc.c **** * Description : Gets the selected ADC reset calibration registers status. + 370:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 371:stm32lib/src/stm32f10x_adc.c **** * Output : None + 372:stm32lib/src/stm32f10x_adc.c **** * Return : The new state of ADC reset calibration registers (SET or RESET). + 373:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 374:stm32lib/src/stm32f10x_adc.c **** FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx) + 375:stm32lib/src/stm32f10x_adc.c **** { + 237 .loc 1 375 0 + 238 @ args = 0, pretend = 0, frame = 0 + 239 @ frame_needed = 0, uses_anonymous_args = 0 + 240 @ link register save eliminated. + 241 .LVL16: + 376:stm32lib/src/stm32f10x_adc.c **** FlagStatus bitstatus = RESET; + 377:stm32lib/src/stm32f10x_adc.c **** + 378:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 379:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 380:stm32lib/src/stm32f10x_adc.c **** + 381:stm32lib/src/stm32f10x_adc.c **** /* Check the status of RSTCAL bit */ + 382:stm32lib/src/stm32f10x_adc.c **** if ((ADCx->CR2 & CR2_RSTCAL_Set) != (u32)RESET) + 242 .loc 1 382 0 + 243 00a8 8068 ldr r0, [r0, #8] + 244 .LVL17: + 383:stm32lib/src/stm32f10x_adc.c **** { + 384:stm32lib/src/stm32f10x_adc.c **** /* RSTCAL bit is set */ + 385:stm32lib/src/stm32f10x_adc.c **** bitstatus = SET; + 386:stm32lib/src/stm32f10x_adc.c **** } + 387:stm32lib/src/stm32f10x_adc.c **** else + 388:stm32lib/src/stm32f10x_adc.c **** { + 389:stm32lib/src/stm32f10x_adc.c **** /* RSTCAL bit is reset */ + 390:stm32lib/src/stm32f10x_adc.c **** bitstatus = RESET; + 391:stm32lib/src/stm32f10x_adc.c **** } + 392:stm32lib/src/stm32f10x_adc.c **** + 393:stm32lib/src/stm32f10x_adc.c **** /* Return the RSTCAL bit status */ + 394:stm32lib/src/stm32f10x_adc.c **** return bitstatus; + 395:stm32lib/src/stm32f10x_adc.c **** } + 245 .loc 1 395 0 + 246 00aa C0F3C000 ubfx r0, r0, #3, #1 + 247 00ae 7047 bx lr + 248 .LFE30: + 250 .align 2 + 251 .global ADC_StartCalibration + 252 .thumb + 253 .thumb_func + 255 ADC_StartCalibration: + 256 .LFB31: + 396:stm32lib/src/stm32f10x_adc.c **** + 397:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 398:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_StartCalibration + 399:stm32lib/src/stm32f10x_adc.c **** * Description : Starts the selected ADC calibration process. + 400:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 401:stm32lib/src/stm32f10x_adc.c **** * Output : None + 402:stm32lib/src/stm32f10x_adc.c **** * Return : None + 403:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 404:stm32lib/src/stm32f10x_adc.c **** void ADC_StartCalibration(ADC_TypeDef* ADCx) + 405:stm32lib/src/stm32f10x_adc.c **** { + 257 .loc 1 405 0 + 258 @ args = 0, pretend = 0, frame = 0 + 259 @ frame_needed = 0, uses_anonymous_args = 0 + 260 @ link register save eliminated. + 261 .LVL18: + 406:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 407:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 408:stm32lib/src/stm32f10x_adc.c **** + 409:stm32lib/src/stm32f10x_adc.c **** /* Enable the selected ADC calibration process */ + 410:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 |= CR2_CAL_Set; + 262 .loc 1 410 0 + 263 00b0 8368 ldr r3, [r0, #8] + 264 00b2 43F00403 orr r3, r3, #4 + 265 00b6 8360 str r3, [r0, #8] + 411:stm32lib/src/stm32f10x_adc.c **** } + 266 .loc 1 411 0 + 267 00b8 7047 bx lr + 268 .LFE31: + 270 00ba 00BF .align 2 + 271 .global ADC_GetCalibrationStatus + 272 .thumb + 273 .thumb_func + 275 ADC_GetCalibrationStatus: + 276 .LFB32: + 412:stm32lib/src/stm32f10x_adc.c **** + 413:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 414:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_GetCalibrationStatus + 415:stm32lib/src/stm32f10x_adc.c **** * Description : Gets the selected ADC calibration status. + 416:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 417:stm32lib/src/stm32f10x_adc.c **** * Output : None + 418:stm32lib/src/stm32f10x_adc.c **** * Return : The new state of ADC calibration (SET or RESET). + 419:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 420:stm32lib/src/stm32f10x_adc.c **** FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx) + 421:stm32lib/src/stm32f10x_adc.c **** { + 277 .loc 1 421 0 + 278 @ args = 0, pretend = 0, frame = 0 + 279 @ frame_needed = 0, uses_anonymous_args = 0 + 280 @ link register save eliminated. + 281 .LVL19: + 422:stm32lib/src/stm32f10x_adc.c **** FlagStatus bitstatus = RESET; + 423:stm32lib/src/stm32f10x_adc.c **** + 424:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 425:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 426:stm32lib/src/stm32f10x_adc.c **** + 427:stm32lib/src/stm32f10x_adc.c **** /* Check the status of CAL bit */ + 428:stm32lib/src/stm32f10x_adc.c **** if ((ADCx->CR2 & CR2_CAL_Set) != (u32)RESET) + 282 .loc 1 428 0 + 283 00bc 8068 ldr r0, [r0, #8] + 284 .LVL20: + 429:stm32lib/src/stm32f10x_adc.c **** { + 430:stm32lib/src/stm32f10x_adc.c **** /* CAL bit is set: calibration on going */ + 431:stm32lib/src/stm32f10x_adc.c **** bitstatus = SET; + 432:stm32lib/src/stm32f10x_adc.c **** } + 433:stm32lib/src/stm32f10x_adc.c **** else + 434:stm32lib/src/stm32f10x_adc.c **** { + 435:stm32lib/src/stm32f10x_adc.c **** /* CAL bit is reset: end of calibration */ + 436:stm32lib/src/stm32f10x_adc.c **** bitstatus = RESET; + 437:stm32lib/src/stm32f10x_adc.c **** } + 438:stm32lib/src/stm32f10x_adc.c **** + 439:stm32lib/src/stm32f10x_adc.c **** /* Return the CAL bit status */ + 440:stm32lib/src/stm32f10x_adc.c **** return bitstatus; + 441:stm32lib/src/stm32f10x_adc.c **** } + 285 .loc 1 441 0 + 286 00be C0F38000 ubfx r0, r0, #2, #1 + 287 00c2 7047 bx lr + 288 .LFE32: + 290 .align 2 + 291 .global ADC_SoftwareStartConvCmd + 292 .thumb + 293 .thumb_func + 295 ADC_SoftwareStartConvCmd: + 296 .LFB33: + 442:stm32lib/src/stm32f10x_adc.c **** + 443:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 444:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_SoftwareStartConvCmd + 445:stm32lib/src/stm32f10x_adc.c **** * Description : Enables or disables the selected ADC software start conversion . + 446:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 447:stm32lib/src/stm32f10x_adc.c **** * - NewState: new state of the selected ADC software start conversion. + 448:stm32lib/src/stm32f10x_adc.c **** * This parameter can be: ENABLE or DISABLE. + 449:stm32lib/src/stm32f10x_adc.c **** * Output : None + 450:stm32lib/src/stm32f10x_adc.c **** * Return : None + 451:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 452:stm32lib/src/stm32f10x_adc.c **** void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) + 453:stm32lib/src/stm32f10x_adc.c **** { + 297 .loc 1 453 0 + 298 @ args = 0, pretend = 0, frame = 0 + 299 @ frame_needed = 0, uses_anonymous_args = 0 + 300 @ link register save eliminated. + 301 .LVL21: + 454:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 455:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 456:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 457:stm32lib/src/stm32f10x_adc.c **** + 458:stm32lib/src/stm32f10x_adc.c **** if (NewState != DISABLE) + 302 .loc 1 458 0 + 303 00c4 19B1 cbz r1, .L31 + 459:stm32lib/src/stm32f10x_adc.c **** { + 460:stm32lib/src/stm32f10x_adc.c **** /* Enable the selected ADC conversion on external event and start the selected + 461:stm32lib/src/stm32f10x_adc.c **** ADC conversion */ + 462:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 |= CR2_EXTTRIG_SWSTART_Set; + 304 .loc 1 462 0 + 305 00c6 8368 ldr r3, [r0, #8] + 306 00c8 43F4A003 orr r3, r3, #5242880 + 307 00cc 02E0 b .L34 + 308 .L31: + 463:stm32lib/src/stm32f10x_adc.c **** } + 464:stm32lib/src/stm32f10x_adc.c **** else + 465:stm32lib/src/stm32f10x_adc.c **** { + 466:stm32lib/src/stm32f10x_adc.c **** /* Disable the selected ADC conversion on external event and stop the selected + 467:stm32lib/src/stm32f10x_adc.c **** ADC conversion */ + 468:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 &= CR2_EXTTRIG_SWSTART_Reset; + 309 .loc 1 468 0 + 310 00ce 8368 ldr r3, [r0, #8] + 311 00d0 23F4A003 bic r3, r3, #5242880 + 312 .L34: + 313 00d4 8360 str r3, [r0, #8] + 469:stm32lib/src/stm32f10x_adc.c **** } + 470:stm32lib/src/stm32f10x_adc.c **** } + 314 .loc 1 470 0 + 315 00d6 7047 bx lr + 316 .LFE33: + 318 .align 2 + 319 .global ADC_GetSoftwareStartConvStatus + 320 .thumb + 321 .thumb_func + 323 ADC_GetSoftwareStartConvStatus: + 324 .LFB34: + 471:stm32lib/src/stm32f10x_adc.c **** + 472:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 473:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_GetSoftwareStartConvStatus + 474:stm32lib/src/stm32f10x_adc.c **** * Description : Gets the selected ADC Software start conversion Status. + 475:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 476:stm32lib/src/stm32f10x_adc.c **** * Output : None + 477:stm32lib/src/stm32f10x_adc.c **** * Return : The new state of ADC software start conversion (SET or RESET). + 478:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 479:stm32lib/src/stm32f10x_adc.c **** FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx) + 480:stm32lib/src/stm32f10x_adc.c **** { + 325 .loc 1 480 0 + 326 @ args = 0, pretend = 0, frame = 0 + 327 @ frame_needed = 0, uses_anonymous_args = 0 + 328 @ link register save eliminated. + 329 .LVL22: + 481:stm32lib/src/stm32f10x_adc.c **** FlagStatus bitstatus = RESET; + 482:stm32lib/src/stm32f10x_adc.c **** + 483:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 484:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 485:stm32lib/src/stm32f10x_adc.c **** + 486:stm32lib/src/stm32f10x_adc.c **** /* Check the status of SWSTART bit */ + 487:stm32lib/src/stm32f10x_adc.c **** if ((ADCx->CR2 & CR2_SWSTART_Set) != (u32)RESET) + 330 .loc 1 487 0 + 331 00d8 8068 ldr r0, [r0, #8] + 332 .LVL23: + 488:stm32lib/src/stm32f10x_adc.c **** { + 489:stm32lib/src/stm32f10x_adc.c **** /* SWSTART bit is set */ + 490:stm32lib/src/stm32f10x_adc.c **** bitstatus = SET; + 491:stm32lib/src/stm32f10x_adc.c **** } + 492:stm32lib/src/stm32f10x_adc.c **** else + 493:stm32lib/src/stm32f10x_adc.c **** { + 494:stm32lib/src/stm32f10x_adc.c **** /* SWSTART bit is reset */ + 495:stm32lib/src/stm32f10x_adc.c **** bitstatus = RESET; + 496:stm32lib/src/stm32f10x_adc.c **** } + 497:stm32lib/src/stm32f10x_adc.c **** + 498:stm32lib/src/stm32f10x_adc.c **** /* Return the SWSTART bit status */ + 499:stm32lib/src/stm32f10x_adc.c **** return bitstatus; + 500:stm32lib/src/stm32f10x_adc.c **** } + 333 .loc 1 500 0 + 334 00da C0F38050 ubfx r0, r0, #22, #1 + 335 00de 7047 bx lr + 336 .LFE34: + 338 .align 2 + 339 .global ADC_DiscModeChannelCountConfig + 340 .thumb + 341 .thumb_func + 343 ADC_DiscModeChannelCountConfig: + 344 .LFB35: + 501:stm32lib/src/stm32f10x_adc.c **** + 502:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 503:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_DiscModeChannelCountConfig + 504:stm32lib/src/stm32f10x_adc.c **** * Description : Configures the discontinuous mode for the selected ADC regular + 505:stm32lib/src/stm32f10x_adc.c **** * group channel. + 506:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 507:stm32lib/src/stm32f10x_adc.c **** * - Number: specifies the discontinuous mode regular channel + 508:stm32lib/src/stm32f10x_adc.c **** * count value. This number must be between 1 and 8. + 509:stm32lib/src/stm32f10x_adc.c **** * Output : None + 510:stm32lib/src/stm32f10x_adc.c **** * Return : None + 511:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 512:stm32lib/src/stm32f10x_adc.c **** void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, u8 Number) + 513:stm32lib/src/stm32f10x_adc.c **** { + 345 .loc 1 513 0 + 346 @ args = 0, pretend = 0, frame = 0 + 347 @ frame_needed = 0, uses_anonymous_args = 0 + 348 @ link register save eliminated. + 349 .LVL24: + 514:stm32lib/src/stm32f10x_adc.c **** u32 tmpreg1 = 0; + 515:stm32lib/src/stm32f10x_adc.c **** u32 tmpreg2 = 0; + 516:stm32lib/src/stm32f10x_adc.c **** + 517:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 518:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 519:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_REGULAR_DISC_NUMBER(Number)); + 520:stm32lib/src/stm32f10x_adc.c **** + 521:stm32lib/src/stm32f10x_adc.c **** /* Get the old register value */ + 522:stm32lib/src/stm32f10x_adc.c **** tmpreg1 = ADCx->CR1; + 350 .loc 1 522 0 + 351 00e0 4368 ldr r3, [r0, #4] + 352 .LVL25: + 523:stm32lib/src/stm32f10x_adc.c **** /* Clear the old discontinuous mode channel count */ + 524:stm32lib/src/stm32f10x_adc.c **** tmpreg1 &= CR1_DISCNUM_Reset; + 525:stm32lib/src/stm32f10x_adc.c **** /* Set the discontinuous mode channel count */ + 526:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = Number - 1; + 527:stm32lib/src/stm32f10x_adc.c **** tmpreg1 |= tmpreg2 << 13; + 353 .loc 1 527 0 + 354 00e2 0139 subs r1, r1, #1 + 355 .LVL26: + 356 .loc 1 524 0 + 357 00e4 23F46043 bic r3, r3, #57344 + 358 .LVL27: + 359 .loc 1 527 0 + 360 00e8 43EA4133 orr r3, r3, r1, lsl #13 + 361 .LVL28: + 528:stm32lib/src/stm32f10x_adc.c **** /* Store the new register value */ + 529:stm32lib/src/stm32f10x_adc.c **** ADCx->CR1 = tmpreg1; + 362 .loc 1 529 0 + 363 00ec 4360 str r3, [r0, #4] + 530:stm32lib/src/stm32f10x_adc.c **** } + 364 .loc 1 530 0 + 365 00ee 7047 bx lr + 366 .LFE35: + 368 .align 2 + 369 .global ADC_DiscModeCmd + 370 .thumb + 371 .thumb_func + 373 ADC_DiscModeCmd: + 374 .LFB36: + 531:stm32lib/src/stm32f10x_adc.c **** + 532:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 533:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_DiscModeCmd + 534:stm32lib/src/stm32f10x_adc.c **** * Description : Enables or disables the discontinuous mode on regular group + 535:stm32lib/src/stm32f10x_adc.c **** * channel for the specified ADC + 536:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 537:stm32lib/src/stm32f10x_adc.c **** * - NewState: new state of the selected ADC discontinuous mode + 538:stm32lib/src/stm32f10x_adc.c **** * on regular group channel. + 539:stm32lib/src/stm32f10x_adc.c **** * This parameter can be: ENABLE or DISABLE. + 540:stm32lib/src/stm32f10x_adc.c **** * Output : None + 541:stm32lib/src/stm32f10x_adc.c **** * Return : None + 542:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 543:stm32lib/src/stm32f10x_adc.c **** void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) + 544:stm32lib/src/stm32f10x_adc.c **** { + 375 .loc 1 544 0 + 376 @ args = 0, pretend = 0, frame = 0 + 377 @ frame_needed = 0, uses_anonymous_args = 0 + 378 @ link register save eliminated. + 379 .LVL29: + 545:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 546:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 547:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 548:stm32lib/src/stm32f10x_adc.c **** + 549:stm32lib/src/stm32f10x_adc.c **** if (NewState != DISABLE) + 380 .loc 1 549 0 + 381 00f0 19B1 cbz r1, .L40 + 550:stm32lib/src/stm32f10x_adc.c **** { + 551:stm32lib/src/stm32f10x_adc.c **** /* Enable the selected ADC regular discontinuous mode */ + 552:stm32lib/src/stm32f10x_adc.c **** ADCx->CR1 |= CR1_DISCEN_Set; + 382 .loc 1 552 0 + 383 00f2 4368 ldr r3, [r0, #4] + 384 00f4 43F40063 orr r3, r3, #2048 + 385 00f8 02E0 b .L43 + 386 .L40: + 553:stm32lib/src/stm32f10x_adc.c **** } + 554:stm32lib/src/stm32f10x_adc.c **** else + 555:stm32lib/src/stm32f10x_adc.c **** { + 556:stm32lib/src/stm32f10x_adc.c **** /* Disable the selected ADC regular discontinuous mode */ + 557:stm32lib/src/stm32f10x_adc.c **** ADCx->CR1 &= CR1_DISCEN_Reset; + 387 .loc 1 557 0 + 388 00fa 4368 ldr r3, [r0, #4] + 389 00fc 23F40063 bic r3, r3, #2048 + 390 .L43: + 391 0100 4360 str r3, [r0, #4] + 558:stm32lib/src/stm32f10x_adc.c **** } + 559:stm32lib/src/stm32f10x_adc.c **** } + 392 .loc 1 559 0 + 393 0102 7047 bx lr + 394 .LFE36: + 396 .align 2 + 397 .global ADC_RegularChannelConfig + 398 .thumb + 399 .thumb_func + 401 ADC_RegularChannelConfig: + 402 .LFB37: + 560:stm32lib/src/stm32f10x_adc.c **** + 561:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 562:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_RegularChannelConfig + 563:stm32lib/src/stm32f10x_adc.c **** * Description : Configures for the selected ADC regular channel its corresponding + 564:stm32lib/src/stm32f10x_adc.c **** * rank in the sequencer and its sample time. + 565:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 566:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel: the ADC channel to configure. + 567:stm32lib/src/stm32f10x_adc.c **** * This parameter can be one of the following values: + 568:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_0: ADC Channel0 selected + 569:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_1: ADC Channel1 selected + 570:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_2: ADC Channel2 selected + 571:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_3: ADC Channel3 selected + 572:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_4: ADC Channel4 selected + 573:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_5: ADC Channel5 selected + 574:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_6: ADC Channel6 selected + 575:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_7: ADC Channel7 selected + 576:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_8: ADC Channel8 selected + 577:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_9: ADC Channel9 selected + 578:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_10: ADC Channel10 selected + 579:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_11: ADC Channel11 selected + 580:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_12: ADC Channel12 selected + 581:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_13: ADC Channel13 selected + 582:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_14: ADC Channel14 selected + 583:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_15: ADC Channel15 selected + 584:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_16: ADC Channel16 selected + 585:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_17: ADC Channel17 selected + 586:stm32lib/src/stm32f10x_adc.c **** * - Rank: The rank in the regular group sequencer. This parameter + 587:stm32lib/src/stm32f10x_adc.c **** * must be between 1 to 16. + 588:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime: The sample time value to be set for the + 589:stm32lib/src/stm32f10x_adc.c **** * selected channel. + 590:stm32lib/src/stm32f10x_adc.c **** * This parameter can be one of the following values: + 591:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles + 592:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles + 593:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles + 594:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles + 595:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles + 596:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles + 597:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles + 598:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles + 599:stm32lib/src/stm32f10x_adc.c **** * Output : None + 600:stm32lib/src/stm32f10x_adc.c **** * Return : None + 601:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 602:stm32lib/src/stm32f10x_adc.c **** void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel, u8 Rank, u8 ADC_SampleTime) + 603:stm32lib/src/stm32f10x_adc.c **** { + 403 .loc 1 603 0 + 404 @ args = 0, pretend = 0, frame = 0 + 405 @ frame_needed = 0, uses_anonymous_args = 0 + 406 .LVL30: + 604:stm32lib/src/stm32f10x_adc.c **** u32 tmpreg1 = 0, tmpreg2 = 0; + 605:stm32lib/src/stm32f10x_adc.c **** + 606:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 607:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 608:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_CHANNEL(ADC_Channel)); + 609:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_REGULAR_RANK(Rank)); + 610:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime)); + 611:stm32lib/src/stm32f10x_adc.c **** + 612:stm32lib/src/stm32f10x_adc.c **** /* if ADC_Channel_10 ... ADC_Channel_17 is selected */ + 613:stm32lib/src/stm32f10x_adc.c **** if (ADC_Channel > ADC_Channel_9) + 407 .loc 1 613 0 + 408 0104 0929 cmp r1, #9 + 409 .loc 1 603 0 + 410 0106 30B5 push {r4, r5, lr} + 411 .LCFI1: + 412 .loc 1 603 0 + 413 0108 9446 mov ip, r2 + 414 010a 0C46 mov r4, r1 + 415 010c 1D46 mov r5, r3 + 416 .loc 1 613 0 + 417 010e 0CD9 bls .L45 + 418 .LVL31: + 614:stm32lib/src/stm32f10x_adc.c **** { + 615:stm32lib/src/stm32f10x_adc.c **** /* Get the old register value */ + 616:stm32lib/src/stm32f10x_adc.c **** tmpreg1 = ADCx->SMPR1; + 617:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to clear */ + 618:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = SMPR1_SMP_Set << (3 * (ADC_Channel - 10)); + 419 .loc 1 618 0 + 420 0110 0322 movs r2, #3 + 421 0112 6243 muls r2, r4, r2 + 619:stm32lib/src/stm32f10x_adc.c **** /* Clear the old discontinuous mode channel count */ + 620:stm32lib/src/stm32f10x_adc.c **** tmpreg1 &= ~tmpreg2; + 422 .loc 1 620 0 + 423 0114 0723 movs r3, #7 + 424 .loc 1 618 0 + 425 0116 1E3A subs r2, r2, #30 + 426 .loc 1 620 0 + 427 0118 9340 lsls r3, r3, r2 + 621:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to set */ + 622:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = (u32)ADC_SampleTime << (3 * (ADC_Channel - 10)); + 623:stm32lib/src/stm32f10x_adc.c **** /* Set the discontinuous mode channel count */ + 624:stm32lib/src/stm32f10x_adc.c **** tmpreg1 |= tmpreg2; + 428 .loc 1 624 0 + 429 011a 15FA02F2 lsls r2, r5, r2 + 430 .loc 1 616 0 + 431 011e C168 ldr r1, [r0, #12] + 432 .LVL32: + 433 .loc 1 620 0 + 434 0120 21EA0301 bic r1, r1, r3 + 435 .LVL33: + 436 .loc 1 624 0 + 437 0124 1143 orrs r1, r1, r2 + 438 .LVL34: + 625:stm32lib/src/stm32f10x_adc.c **** /* Store the new register value */ + 626:stm32lib/src/stm32f10x_adc.c **** ADCx->SMPR1 = tmpreg1; + 439 .loc 1 626 0 + 440 0126 C160 str r1, [r0, #12] + 441 0128 0AE0 b .L46 + 442 .LVL35: + 443 .L45: + 627:stm32lib/src/stm32f10x_adc.c **** } + 628:stm32lib/src/stm32f10x_adc.c **** else /* ADC_Channel include in ADC_Channel_[0..9] */ + 629:stm32lib/src/stm32f10x_adc.c **** { + 630:stm32lib/src/stm32f10x_adc.c **** /* Get the old register value */ + 631:stm32lib/src/stm32f10x_adc.c **** tmpreg1 = ADCx->SMPR2; + 632:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to clear */ + 633:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel); + 444 .loc 1 633 0 + 445 012a 0322 movs r2, #3 + 446 012c 6243 muls r2, r4, r2 + 634:stm32lib/src/stm32f10x_adc.c **** /* Clear the old discontinuous mode channel count */ + 635:stm32lib/src/stm32f10x_adc.c **** tmpreg1 &= ~tmpreg2; + 447 .loc 1 635 0 + 448 012e 0723 movs r3, #7 + 449 0130 9340 lsls r3, r3, r2 + 636:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to set */ + 637:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = (u32)ADC_SampleTime << (3 * ADC_Channel); + 638:stm32lib/src/stm32f10x_adc.c **** /* Set the discontinuous mode channel count */ + 639:stm32lib/src/stm32f10x_adc.c **** tmpreg1 |= tmpreg2; + 450 .loc 1 639 0 + 451 0132 15FA02F2 lsls r2, r5, r2 + 452 .loc 1 631 0 + 453 0136 0169 ldr r1, [r0, #16] + 454 .LVL36: + 455 .loc 1 635 0 + 456 0138 21EA0301 bic r1, r1, r3 + 457 .LVL37: + 458 .loc 1 639 0 + 459 013c 1143 orrs r1, r1, r2 + 460 .LVL38: + 640:stm32lib/src/stm32f10x_adc.c **** /* Store the new register value */ + 641:stm32lib/src/stm32f10x_adc.c **** ADCx->SMPR2 = tmpreg1; + 461 .loc 1 641 0 + 462 013e 0161 str r1, [r0, #16] + 463 .L46: + 642:stm32lib/src/stm32f10x_adc.c **** } + 643:stm32lib/src/stm32f10x_adc.c **** /* For Rank 1 to 6 */ + 644:stm32lib/src/stm32f10x_adc.c **** if (Rank < 7) + 464 .loc 1 644 0 + 465 0140 BCF1060F cmp ip, #6 + 466 0144 0DD8 bhi .L47 + 645:stm32lib/src/stm32f10x_adc.c **** { + 646:stm32lib/src/stm32f10x_adc.c **** /* Get the old register value */ + 647:stm32lib/src/stm32f10x_adc.c **** tmpreg1 = ADCx->SQR3; + 648:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to clear */ + 649:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = SQR3_SQ_Set << (5 * (Rank - 1)); + 467 .loc 1 649 0 + 468 0146 0522 movs r2, #5 + 469 0148 02FB0CF2 mul r2, r2, ip + 650:stm32lib/src/stm32f10x_adc.c **** /* Clear the old SQx bits for the selected rank */ + 651:stm32lib/src/stm32f10x_adc.c **** tmpreg1 &= ~tmpreg2; + 470 .loc 1 651 0 + 471 014c 1F23 movs r3, #31 + 472 .loc 1 649 0 + 473 014e 053A subs r2, r2, #5 + 474 .loc 1 651 0 + 475 0150 9340 lsls r3, r3, r2 + 652:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to set */ + 653:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = (u32)ADC_Channel << (5 * (Rank - 1)); + 654:stm32lib/src/stm32f10x_adc.c **** /* Set the SQx bits for the selected rank */ + 655:stm32lib/src/stm32f10x_adc.c **** tmpreg1 |= tmpreg2; + 476 .loc 1 655 0 + 477 0152 14FA02F2 lsls r2, r4, r2 + 478 .loc 1 647 0 + 479 0156 416B ldr r1, [r0, #52] + 480 .LVL39: + 481 .loc 1 651 0 + 482 0158 21EA0301 bic r1, r1, r3 + 483 .LVL40: + 484 .loc 1 655 0 + 485 015c 1143 orrs r1, r1, r2 + 486 .LVL41: + 656:stm32lib/src/stm32f10x_adc.c **** /* Store the new register value */ + 657:stm32lib/src/stm32f10x_adc.c **** ADCx->SQR3 = tmpreg1; + 487 .loc 1 657 0 + 488 015e 4163 str r1, [r0, #52] + 489 0160 1DE0 b .L50 + 490 .L47: + 658:stm32lib/src/stm32f10x_adc.c **** } + 659:stm32lib/src/stm32f10x_adc.c **** /* For Rank 7 to 12 */ + 660:stm32lib/src/stm32f10x_adc.c **** else if (Rank < 13) + 491 .loc 1 660 0 + 492 0162 BCF10C0F cmp ip, #12 + 493 0166 0DD8 bhi .L49 + 661:stm32lib/src/stm32f10x_adc.c **** { + 662:stm32lib/src/stm32f10x_adc.c **** /* Get the old register value */ + 663:stm32lib/src/stm32f10x_adc.c **** tmpreg1 = ADCx->SQR2; + 664:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to clear */ + 665:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = SQR2_SQ_Set << (5 * (Rank - 7)); + 494 .loc 1 665 0 + 495 0168 0522 movs r2, #5 + 496 016a 02FB0CF2 mul r2, r2, ip + 666:stm32lib/src/stm32f10x_adc.c **** /* Clear the old SQx bits for the selected rank */ + 667:stm32lib/src/stm32f10x_adc.c **** tmpreg1 &= ~tmpreg2; + 497 .loc 1 667 0 + 498 016e 1F23 movs r3, #31 + 499 .loc 1 665 0 + 500 0170 233A subs r2, r2, #35 + 501 .loc 1 667 0 + 502 0172 9340 lsls r3, r3, r2 + 668:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to set */ + 669:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = (u32)ADC_Channel << (5 * (Rank - 7)); + 670:stm32lib/src/stm32f10x_adc.c **** /* Set the SQx bits for the selected rank */ + 671:stm32lib/src/stm32f10x_adc.c **** tmpreg1 |= tmpreg2; + 503 .loc 1 671 0 + 504 0174 14FA02F2 lsls r2, r4, r2 + 505 .loc 1 663 0 + 506 0178 016B ldr r1, [r0, #48] + 507 .LVL42: + 508 .loc 1 667 0 + 509 017a 21EA0301 bic r1, r1, r3 + 510 .LVL43: + 511 .loc 1 671 0 + 512 017e 1143 orrs r1, r1, r2 + 513 .LVL44: + 672:stm32lib/src/stm32f10x_adc.c **** /* Store the new register value */ + 673:stm32lib/src/stm32f10x_adc.c **** ADCx->SQR2 = tmpreg1; + 514 .loc 1 673 0 + 515 0180 0163 str r1, [r0, #48] + 516 0182 0CE0 b .L50 + 517 .L49: + 674:stm32lib/src/stm32f10x_adc.c **** } + 675:stm32lib/src/stm32f10x_adc.c **** /* For Rank 13 to 16 */ + 676:stm32lib/src/stm32f10x_adc.c **** else + 677:stm32lib/src/stm32f10x_adc.c **** { + 678:stm32lib/src/stm32f10x_adc.c **** /* Get the old register value */ + 679:stm32lib/src/stm32f10x_adc.c **** tmpreg1 = ADCx->SQR1; + 680:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to clear */ + 681:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = SQR1_SQ_Set << (5 * (Rank - 13)); + 518 .loc 1 681 0 + 519 0184 0522 movs r2, #5 + 520 0186 02FB0CF2 mul r2, r2, ip + 682:stm32lib/src/stm32f10x_adc.c **** /* Clear the old SQx bits for the selected rank */ + 683:stm32lib/src/stm32f10x_adc.c **** tmpreg1 &= ~tmpreg2; + 521 .loc 1 683 0 + 522 018a 1F23 movs r3, #31 + 523 .loc 1 681 0 + 524 018c 413A subs r2, r2, #65 + 525 .loc 1 683 0 + 526 018e 9340 lsls r3, r3, r2 + 684:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to set */ + 685:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = (u32)ADC_Channel << (5 * (Rank - 13)); + 686:stm32lib/src/stm32f10x_adc.c **** /* Set the SQx bits for the selected rank */ + 687:stm32lib/src/stm32f10x_adc.c **** tmpreg1 |= tmpreg2; + 527 .loc 1 687 0 + 528 0190 14FA02F2 lsls r2, r4, r2 + 529 .loc 1 679 0 + 530 0194 C16A ldr r1, [r0, #44] + 531 .LVL45: + 532 .loc 1 683 0 + 533 0196 21EA0301 bic r1, r1, r3 + 534 .LVL46: + 535 .loc 1 687 0 + 536 019a 1143 orrs r1, r1, r2 + 537 .LVL47: + 688:stm32lib/src/stm32f10x_adc.c **** /* Store the new register value */ + 689:stm32lib/src/stm32f10x_adc.c **** ADCx->SQR1 = tmpreg1; + 538 .loc 1 689 0 + 539 019c C162 str r1, [r0, #44] + 540 .L50: + 690:stm32lib/src/stm32f10x_adc.c **** } + 691:stm32lib/src/stm32f10x_adc.c **** } + 541 .loc 1 691 0 + 542 019e 30BD pop {r4, r5, pc} + 543 .LFE37: + 545 .align 2 + 546 .global ADC_ExternalTrigConvCmd + 547 .thumb + 548 .thumb_func + 550 ADC_ExternalTrigConvCmd: + 551 .LFB38: + 692:stm32lib/src/stm32f10x_adc.c **** + 693:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 694:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_ExternalTrigConvCmd + 695:stm32lib/src/stm32f10x_adc.c **** * Description : Enables or disables the ADCx conversion through external trigger. + 696:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 697:stm32lib/src/stm32f10x_adc.c **** * - NewState: new state of the selected ADC external trigger + 698:stm32lib/src/stm32f10x_adc.c **** * start of conversion. + 699:stm32lib/src/stm32f10x_adc.c **** * This parameter can be: ENABLE or DISABLE. + 700:stm32lib/src/stm32f10x_adc.c **** * Output : None + 701:stm32lib/src/stm32f10x_adc.c **** * Return : None + 702:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 703:stm32lib/src/stm32f10x_adc.c **** void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) + 704:stm32lib/src/stm32f10x_adc.c **** { + 552 .loc 1 704 0 + 553 @ args = 0, pretend = 0, frame = 0 + 554 @ frame_needed = 0, uses_anonymous_args = 0 + 555 @ link register save eliminated. + 556 .LVL48: + 705:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 706:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 707:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 708:stm32lib/src/stm32f10x_adc.c **** + 709:stm32lib/src/stm32f10x_adc.c **** if (NewState != DISABLE) + 557 .loc 1 709 0 + 558 01a0 19B1 cbz r1, .L52 + 710:stm32lib/src/stm32f10x_adc.c **** { + 711:stm32lib/src/stm32f10x_adc.c **** /* Enable the selected ADC conversion on external event */ + 712:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 |= CR2_EXTTRIG_Set; + 559 .loc 1 712 0 + 560 01a2 8368 ldr r3, [r0, #8] + 561 01a4 43F48013 orr r3, r3, #1048576 + 562 01a8 02E0 b .L55 + 563 .L52: + 713:stm32lib/src/stm32f10x_adc.c **** } + 714:stm32lib/src/stm32f10x_adc.c **** else + 715:stm32lib/src/stm32f10x_adc.c **** { + 716:stm32lib/src/stm32f10x_adc.c **** /* Disable the selected ADC conversion on external event */ + 717:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 &= CR2_EXTTRIG_Reset; + 564 .loc 1 717 0 + 565 01aa 8368 ldr r3, [r0, #8] + 566 01ac 23F48013 bic r3, r3, #1048576 + 567 .L55: + 568 01b0 8360 str r3, [r0, #8] + 718:stm32lib/src/stm32f10x_adc.c **** } + 719:stm32lib/src/stm32f10x_adc.c **** } + 569 .loc 1 719 0 + 570 01b2 7047 bx lr + 571 .LFE38: + 573 .align 2 + 574 .global ADC_GetConversionValue + 575 .thumb + 576 .thumb_func + 578 ADC_GetConversionValue: + 579 .LFB39: + 720:stm32lib/src/stm32f10x_adc.c **** + 721:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 722:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_GetConversionValue + 723:stm32lib/src/stm32f10x_adc.c **** * Description : Returns the last ADCx conversion result data for regular channel. + 724:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 725:stm32lib/src/stm32f10x_adc.c **** * Output : None + 726:stm32lib/src/stm32f10x_adc.c **** * Return : The Data conversion value. + 727:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 728:stm32lib/src/stm32f10x_adc.c **** u16 ADC_GetConversionValue(ADC_TypeDef* ADCx) + 729:stm32lib/src/stm32f10x_adc.c **** { + 580 .loc 1 729 0 + 581 @ args = 0, pretend = 0, frame = 0 + 582 @ frame_needed = 0, uses_anonymous_args = 0 + 583 @ link register save eliminated. + 584 .LVL49: + 730:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 731:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 732:stm32lib/src/stm32f10x_adc.c **** + 733:stm32lib/src/stm32f10x_adc.c **** /* Return the selected ADC conversion value */ + 734:stm32lib/src/stm32f10x_adc.c **** return (u16) ADCx->DR; + 585 .loc 1 734 0 + 586 01b4 C06C ldr r0, [r0, #76] + 587 .LVL50: + 735:stm32lib/src/stm32f10x_adc.c **** } + 588 .loc 1 735 0 + 589 01b6 80B2 uxth r0, r0 + 590 01b8 7047 bx lr + 591 .LFE39: + 593 01ba 00BF .align 2 + 594 .global ADC_GetDualModeConversionValue + 595 .thumb + 596 .thumb_func + 598 ADC_GetDualModeConversionValue: + 599 .LFB40: + 736:stm32lib/src/stm32f10x_adc.c **** + 737:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 738:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_GetDualModeConversionValue + 739:stm32lib/src/stm32f10x_adc.c **** * Description : Returns the last ADC1 and ADC2 conversion result data in dual mode. + 740:stm32lib/src/stm32f10x_adc.c **** * Output : None + 741:stm32lib/src/stm32f10x_adc.c **** * Return : The Data conversion value. + 742:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 743:stm32lib/src/stm32f10x_adc.c **** u32 ADC_GetDualModeConversionValue(void) + 744:stm32lib/src/stm32f10x_adc.c **** { + 600 .loc 1 744 0 + 601 @ args = 0, pretend = 0, frame = 0 + 602 @ frame_needed = 0, uses_anonymous_args = 0 + 603 @ link register save eliminated. + 745:stm32lib/src/stm32f10x_adc.c **** /* Return the dual mode conversion value */ + 746:stm32lib/src/stm32f10x_adc.c **** return (*(vu32 *) DR_ADDRESS); + 604 .loc 1 746 0 + 605 01bc 014B ldr r3, .L60 + 606 01be 1868 ldr r0, [r3, #0] + 747:stm32lib/src/stm32f10x_adc.c **** } + 607 .loc 1 747 0 + 608 01c0 7047 bx lr + 609 .L61: + 610 01c2 00BF .align 2 + 611 .L60: + 612 01c4 4C240140 .word 1073816652 + 613 .LFE40: + 615 .align 2 + 616 .global ADC_AutoInjectedConvCmd + 617 .thumb + 618 .thumb_func + 620 ADC_AutoInjectedConvCmd: + 621 .LFB41: + 748:stm32lib/src/stm32f10x_adc.c **** + 749:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 750:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_AutoInjectedConvCmd + 751:stm32lib/src/stm32f10x_adc.c **** * Description : Enables or disables the selected ADC automatic injected group + 752:stm32lib/src/stm32f10x_adc.c **** * conversion after regular one. + 753:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 754:stm32lib/src/stm32f10x_adc.c **** * - NewState: new state of the selected ADC auto injected + 755:stm32lib/src/stm32f10x_adc.c **** * conversion + 756:stm32lib/src/stm32f10x_adc.c **** * This parameter can be: ENABLE or DISABLE. + 757:stm32lib/src/stm32f10x_adc.c **** * Output : None + 758:stm32lib/src/stm32f10x_adc.c **** * Return : None + 759:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 760:stm32lib/src/stm32f10x_adc.c **** void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) + 761:stm32lib/src/stm32f10x_adc.c **** { + 622 .loc 1 761 0 + 623 @ args = 0, pretend = 0, frame = 0 + 624 @ frame_needed = 0, uses_anonymous_args = 0 + 625 @ link register save eliminated. + 626 .LVL51: + 762:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 763:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 764:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 765:stm32lib/src/stm32f10x_adc.c **** + 766:stm32lib/src/stm32f10x_adc.c **** if (NewState != DISABLE) + 627 .loc 1 766 0 + 628 01c8 19B1 cbz r1, .L63 + 767:stm32lib/src/stm32f10x_adc.c **** { + 768:stm32lib/src/stm32f10x_adc.c **** /* Enable the selected ADC automatic injected group conversion */ + 769:stm32lib/src/stm32f10x_adc.c **** ADCx->CR1 |= CR1_JAUTO_Set; + 629 .loc 1 769 0 + 630 01ca 4368 ldr r3, [r0, #4] + 631 01cc 43F48063 orr r3, r3, #1024 + 632 01d0 02E0 b .L66 + 633 .L63: + 770:stm32lib/src/stm32f10x_adc.c **** } + 771:stm32lib/src/stm32f10x_adc.c **** else + 772:stm32lib/src/stm32f10x_adc.c **** { + 773:stm32lib/src/stm32f10x_adc.c **** /* Disable the selected ADC automatic injected group conversion */ + 774:stm32lib/src/stm32f10x_adc.c **** ADCx->CR1 &= CR1_JAUTO_Reset; + 634 .loc 1 774 0 + 635 01d2 4368 ldr r3, [r0, #4] + 636 01d4 23F48063 bic r3, r3, #1024 + 637 .L66: + 638 01d8 4360 str r3, [r0, #4] + 775:stm32lib/src/stm32f10x_adc.c **** } + 776:stm32lib/src/stm32f10x_adc.c **** } + 639 .loc 1 776 0 + 640 01da 7047 bx lr + 641 .LFE41: + 643 .align 2 + 644 .global ADC_InjectedDiscModeCmd + 645 .thumb + 646 .thumb_func + 648 ADC_InjectedDiscModeCmd: + 649 .LFB42: + 777:stm32lib/src/stm32f10x_adc.c **** + 778:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 779:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_InjectedDiscModeCmd + 780:stm32lib/src/stm32f10x_adc.c **** * Description : Enables or disables the discontinuous mode for injected group + 781:stm32lib/src/stm32f10x_adc.c **** * channel for the specified ADC + 782:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 783:stm32lib/src/stm32f10x_adc.c **** * - NewState: new state of the selected ADC discontinuous mode + 784:stm32lib/src/stm32f10x_adc.c **** * on injected group channel. + 785:stm32lib/src/stm32f10x_adc.c **** * This parameter can be: ENABLE or DISABLE. + 786:stm32lib/src/stm32f10x_adc.c **** * Output : None + 787:stm32lib/src/stm32f10x_adc.c **** * Return : None + 788:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 789:stm32lib/src/stm32f10x_adc.c **** void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) + 790:stm32lib/src/stm32f10x_adc.c **** { + 650 .loc 1 790 0 + 651 @ args = 0, pretend = 0, frame = 0 + 652 @ frame_needed = 0, uses_anonymous_args = 0 + 653 @ link register save eliminated. + 654 .LVL52: + 791:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 792:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 793:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 794:stm32lib/src/stm32f10x_adc.c **** + 795:stm32lib/src/stm32f10x_adc.c **** if (NewState != DISABLE) + 655 .loc 1 795 0 + 656 01dc 19B1 cbz r1, .L68 + 796:stm32lib/src/stm32f10x_adc.c **** { + 797:stm32lib/src/stm32f10x_adc.c **** /* Enable the selected ADC injected discontinuous mode */ + 798:stm32lib/src/stm32f10x_adc.c **** ADCx->CR1 |= CR1_JDISCEN_Set; + 657 .loc 1 798 0 + 658 01de 4368 ldr r3, [r0, #4] + 659 01e0 43F48053 orr r3, r3, #4096 + 660 01e4 02E0 b .L71 + 661 .L68: + 799:stm32lib/src/stm32f10x_adc.c **** } + 800:stm32lib/src/stm32f10x_adc.c **** else + 801:stm32lib/src/stm32f10x_adc.c **** { + 802:stm32lib/src/stm32f10x_adc.c **** /* Disable the selected ADC injected discontinuous mode */ + 803:stm32lib/src/stm32f10x_adc.c **** ADCx->CR1 &= CR1_JDISCEN_Reset; + 662 .loc 1 803 0 + 663 01e6 4368 ldr r3, [r0, #4] + 664 01e8 23F48053 bic r3, r3, #4096 + 665 .L71: + 666 01ec 4360 str r3, [r0, #4] + 804:stm32lib/src/stm32f10x_adc.c **** } + 805:stm32lib/src/stm32f10x_adc.c **** } + 667 .loc 1 805 0 + 668 01ee 7047 bx lr + 669 .LFE42: + 671 .align 2 + 672 .global ADC_ExternalTrigInjectedConvConfig + 673 .thumb + 674 .thumb_func + 676 ADC_ExternalTrigInjectedConvConfig: + 677 .LFB43: + 806:stm32lib/src/stm32f10x_adc.c **** + 807:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 808:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_ExternalTrigInjectedConvConfig + 809:stm32lib/src/stm32f10x_adc.c **** * Description : Configures the ADCx external trigger for injected channels conversion. + 810:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 811:stm32lib/src/stm32f10x_adc.c **** * - ADC_ExternalTrigInjecConv: specifies the ADC trigger to + 812:stm32lib/src/stm32f10x_adc.c **** * start injected conversion. + 813:stm32lib/src/stm32f10x_adc.c **** * This parameter can be one of the following values: + 814:stm32lib/src/stm32f10x_adc.c **** * - ADC_ExternalTrigInjecConv_T1_TRGO: Timer1 TRGO event + 815:stm32lib/src/stm32f10x_adc.c **** * selected (for ADC1, ADC2 and ADC3) + 816:stm32lib/src/stm32f10x_adc.c **** * - ADC_ExternalTrigInjecConv_T1_CC4: Timer1 capture + 817:stm32lib/src/stm32f10x_adc.c **** * compare4 selected (for ADC1, ADC2 and ADC3) + 818:stm32lib/src/stm32f10x_adc.c **** * - ADC_ExternalTrigInjecConv_T2_TRGO: Timer2 TRGO event + 819:stm32lib/src/stm32f10x_adc.c **** * selected (for ADC1 and ADC2) + 820:stm32lib/src/stm32f10x_adc.c **** * - ADC_External TrigInjecConv_T2_CC1: Timer2 capture + 821:stm32lib/src/stm32f10x_adc.c **** * compare1 selected (for ADC1 and ADC2) + 822:stm32lib/src/stm32f10x_adc.c **** * - ADC_ExternalTrigInjecConv_T3_CC4: Timer3 capture + 823:stm32lib/src/stm32f10x_adc.c **** * compare4 selected (for ADC1 and ADC2) + 824:stm32lib/src/stm32f10x_adc.c **** * - ADC_ExternalTrigInjecConv_T4_TRGO: Timer4 TRGO event + 825:stm32lib/src/stm32f10x_adc.c **** * selected (for ADC1 and ADC2) + 826:stm32lib/src/stm32f10x_adc.c **** * - ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4: External + 827:stm32lib/src/stm32f10x_adc.c **** * interrupt line 15 or Timer8 capture compare4 event selected + 828:stm32lib/src/stm32f10x_adc.c **** * (for ADC1 and ADC2) + 829:stm32lib/src/stm32f10x_adc.c **** * - ADC_External TrigInjecConv_T4_CC3: Timer4 capture + 830:stm32lib/src/stm32f10x_adc.c **** * compare3 selected (for ADC3 only) + 831:stm32lib/src/stm32f10x_adc.c **** * - ADC_External TrigInjecConv_T8_CC2: Timer8 capture + 832:stm32lib/src/stm32f10x_adc.c **** * compare2 selected (for ADC3 only) + 833:stm32lib/src/stm32f10x_adc.c **** * - ADC_External TrigInjecConv_T8_CC4: Timer8 capture + 834:stm32lib/src/stm32f10x_adc.c **** * compare4 selected (for ADC3 only) + 835:stm32lib/src/stm32f10x_adc.c **** * - ADC_ExternalTrigInjecConv_T5_TRGO: Timer5 TRGO event + 836:stm32lib/src/stm32f10x_adc.c **** * selected (for ADC3 only) + 837:stm32lib/src/stm32f10x_adc.c **** * - ADC_External TrigInjecConv_T5_CC4: Timer5 capture + 838:stm32lib/src/stm32f10x_adc.c **** * compare4 selected (for ADC3 only) + 839:stm32lib/src/stm32f10x_adc.c **** * - ADC_ExternalTrigInjecConv_None: Injected conversion + 840:stm32lib/src/stm32f10x_adc.c **** * started by software and not by external trigger (for + 841:stm32lib/src/stm32f10x_adc.c **** * ADC1, ADC2 and ADC3) + 842:stm32lib/src/stm32f10x_adc.c **** * Output : None + 843:stm32lib/src/stm32f10x_adc.c **** * Return : None + 844:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 845:stm32lib/src/stm32f10x_adc.c **** void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, u32 ADC_ExternalTrigInjecConv) + 846:stm32lib/src/stm32f10x_adc.c **** { + 678 .loc 1 846 0 + 679 @ args = 0, pretend = 0, frame = 0 + 680 @ frame_needed = 0, uses_anonymous_args = 0 + 681 @ link register save eliminated. + 682 .LVL53: + 847:stm32lib/src/stm32f10x_adc.c **** u32 tmpreg = 0; + 848:stm32lib/src/stm32f10x_adc.c **** + 849:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 850:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 851:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_EXT_INJEC_TRIG(ADC_ExternalTrigInjecConv)); + 852:stm32lib/src/stm32f10x_adc.c **** + 853:stm32lib/src/stm32f10x_adc.c **** /* Get the old register value */ + 854:stm32lib/src/stm32f10x_adc.c **** tmpreg = ADCx->CR2; + 683 .loc 1 854 0 + 684 01f0 8368 ldr r3, [r0, #8] + 685 .LVL54: + 855:stm32lib/src/stm32f10x_adc.c **** /* Clear the old external event selection for injected group */ + 856:stm32lib/src/stm32f10x_adc.c **** tmpreg &= CR2_JEXTSEL_Reset; + 686 .loc 1 856 0 + 687 01f2 23F4E043 bic r3, r3, #28672 + 688 .LVL55: + 857:stm32lib/src/stm32f10x_adc.c **** /* Set the external event selection for injected group */ + 858:stm32lib/src/stm32f10x_adc.c **** tmpreg |= ADC_ExternalTrigInjecConv; + 689 .loc 1 858 0 + 690 01f6 1943 orrs r1, r1, r3 + 691 .LVL56: + 859:stm32lib/src/stm32f10x_adc.c **** /* Store the new register value */ + 860:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 = tmpreg; + 692 .loc 1 860 0 + 693 01f8 8160 str r1, [r0, #8] + 861:stm32lib/src/stm32f10x_adc.c **** } + 694 .loc 1 861 0 + 695 01fa 7047 bx lr + 696 .LFE43: + 698 .align 2 + 699 .global ADC_ExternalTrigInjectedConvCmd + 700 .thumb + 701 .thumb_func + 703 ADC_ExternalTrigInjectedConvCmd: + 704 .LFB44: + 862:stm32lib/src/stm32f10x_adc.c **** + 863:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 864:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_ExternalTrigInjectedConvCmd + 865:stm32lib/src/stm32f10x_adc.c **** * Description : Enables or disables the ADCx injected channels conversion + 866:stm32lib/src/stm32f10x_adc.c **** * through external trigger + 867:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 868:stm32lib/src/stm32f10x_adc.c **** * - NewState: new state of the selected ADC external trigger + 869:stm32lib/src/stm32f10x_adc.c **** * start of injected conversion. + 870:stm32lib/src/stm32f10x_adc.c **** * This parameter can be: ENABLE or DISABLE. + 871:stm32lib/src/stm32f10x_adc.c **** * Output : None + 872:stm32lib/src/stm32f10x_adc.c **** * Return : None + 873:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 874:stm32lib/src/stm32f10x_adc.c **** void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) + 875:stm32lib/src/stm32f10x_adc.c **** { + 705 .loc 1 875 0 + 706 @ args = 0, pretend = 0, frame = 0 + 707 @ frame_needed = 0, uses_anonymous_args = 0 + 708 @ link register save eliminated. + 709 .LVL57: + 876:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 877:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 878:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 879:stm32lib/src/stm32f10x_adc.c **** + 880:stm32lib/src/stm32f10x_adc.c **** if (NewState != DISABLE) + 710 .loc 1 880 0 + 711 01fc 19B1 cbz r1, .L75 + 881:stm32lib/src/stm32f10x_adc.c **** { + 882:stm32lib/src/stm32f10x_adc.c **** /* Enable the selected ADC external event selection for injected group */ + 883:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 |= CR2_JEXTTRIG_Set; + 712 .loc 1 883 0 + 713 01fe 8368 ldr r3, [r0, #8] + 714 0200 43F40043 orr r3, r3, #32768 + 715 0204 02E0 b .L78 + 716 .L75: + 884:stm32lib/src/stm32f10x_adc.c **** } + 885:stm32lib/src/stm32f10x_adc.c **** else + 886:stm32lib/src/stm32f10x_adc.c **** { + 887:stm32lib/src/stm32f10x_adc.c **** /* Disable the selected ADC external event selection for injected group */ + 888:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 &= CR2_JEXTTRIG_Reset; + 717 .loc 1 888 0 + 718 0206 8368 ldr r3, [r0, #8] + 719 0208 23F40043 bic r3, r3, #32768 + 720 .L78: + 721 020c 8360 str r3, [r0, #8] + 889:stm32lib/src/stm32f10x_adc.c **** } + 890:stm32lib/src/stm32f10x_adc.c **** } + 722 .loc 1 890 0 + 723 020e 7047 bx lr + 724 .LFE44: + 726 .align 2 + 727 .global ADC_SoftwareStartInjectedConvCmd + 728 .thumb + 729 .thumb_func + 731 ADC_SoftwareStartInjectedConvCmd: + 732 .LFB45: + 891:stm32lib/src/stm32f10x_adc.c **** + 892:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 893:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_SoftwareStartInjectedConvCmd + 894:stm32lib/src/stm32f10x_adc.c **** * Description : Enables or disables the selected ADC start of the injected + 895:stm32lib/src/stm32f10x_adc.c **** * channels conversion. + 896:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 897:stm32lib/src/stm32f10x_adc.c **** * - NewState: new state of the selected ADC software start + 898:stm32lib/src/stm32f10x_adc.c **** * injected conversion. + 899:stm32lib/src/stm32f10x_adc.c **** * This parameter can be: ENABLE or DISABLE. + 900:stm32lib/src/stm32f10x_adc.c **** * Output : None + 901:stm32lib/src/stm32f10x_adc.c **** * Return : None + 902:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 903:stm32lib/src/stm32f10x_adc.c **** void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) + 904:stm32lib/src/stm32f10x_adc.c **** { + 733 .loc 1 904 0 + 734 @ args = 0, pretend = 0, frame = 0 + 735 @ frame_needed = 0, uses_anonymous_args = 0 + 736 @ link register save eliminated. + 737 .LVL58: + 905:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 906:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 907:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 908:stm32lib/src/stm32f10x_adc.c **** + 909:stm32lib/src/stm32f10x_adc.c **** if (NewState != DISABLE) + 738 .loc 1 909 0 + 739 0210 19B1 cbz r1, .L80 + 910:stm32lib/src/stm32f10x_adc.c **** { + 911:stm32lib/src/stm32f10x_adc.c **** /* Enable the selected ADC conversion for injected group on external event and start the select + 912:stm32lib/src/stm32f10x_adc.c **** ADC injected conversion */ + 913:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 |= CR2_JEXTTRIG_JSWSTART_Set; + 740 .loc 1 913 0 + 741 0212 8368 ldr r3, [r0, #8] + 742 0214 43F40213 orr r3, r3, #2129920 + 743 0218 02E0 b .L83 + 744 .L80: + 914:stm32lib/src/stm32f10x_adc.c **** } + 915:stm32lib/src/stm32f10x_adc.c **** else + 916:stm32lib/src/stm32f10x_adc.c **** { + 917:stm32lib/src/stm32f10x_adc.c **** /* Disable the selected ADC conversion on external event for injected group and stop the select + 918:stm32lib/src/stm32f10x_adc.c **** ADC injected conversion */ + 919:stm32lib/src/stm32f10x_adc.c **** ADCx->CR2 &= CR2_JEXTTRIG_JSWSTART_Reset; + 745 .loc 1 919 0 + 746 021a 8368 ldr r3, [r0, #8] + 747 021c 23F40213 bic r3, r3, #2129920 + 748 .L83: + 749 0220 8360 str r3, [r0, #8] + 920:stm32lib/src/stm32f10x_adc.c **** } + 921:stm32lib/src/stm32f10x_adc.c **** } + 750 .loc 1 921 0 + 751 0222 7047 bx lr + 752 .LFE45: + 754 .align 2 + 755 .global ADC_GetSoftwareStartInjectedConvCmdStatus + 756 .thumb + 757 .thumb_func + 759 ADC_GetSoftwareStartInjectedConvCmdStatus: + 760 .LFB46: + 922:stm32lib/src/stm32f10x_adc.c **** + 923:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 924:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_GetSoftwareStartInjectedConvCmdStatus + 925:stm32lib/src/stm32f10x_adc.c **** * Description : Gets the selected ADC Software start injected conversion Status. + 926:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 927:stm32lib/src/stm32f10x_adc.c **** * Output : None + 928:stm32lib/src/stm32f10x_adc.c **** * Return : The new state of ADC software start injected conversion (SET or RESET). + 929:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 930:stm32lib/src/stm32f10x_adc.c **** FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx) + 931:stm32lib/src/stm32f10x_adc.c **** { + 761 .loc 1 931 0 + 762 @ args = 0, pretend = 0, frame = 0 + 763 @ frame_needed = 0, uses_anonymous_args = 0 + 764 @ link register save eliminated. + 765 .LVL59: + 932:stm32lib/src/stm32f10x_adc.c **** FlagStatus bitstatus = RESET; + 933:stm32lib/src/stm32f10x_adc.c **** + 934:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 935:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); + 936:stm32lib/src/stm32f10x_adc.c **** + 937:stm32lib/src/stm32f10x_adc.c **** /* Check the status of JSWSTART bit */ + 938:stm32lib/src/stm32f10x_adc.c **** if ((ADCx->CR2 & CR2_JSWSTART_Set) != (u32)RESET) + 766 .loc 1 938 0 + 767 0224 8068 ldr r0, [r0, #8] + 768 .LVL60: + 939:stm32lib/src/stm32f10x_adc.c **** { + 940:stm32lib/src/stm32f10x_adc.c **** /* JSWSTART bit is set */ + 941:stm32lib/src/stm32f10x_adc.c **** bitstatus = SET; + 942:stm32lib/src/stm32f10x_adc.c **** } + 943:stm32lib/src/stm32f10x_adc.c **** else + 944:stm32lib/src/stm32f10x_adc.c **** { + 945:stm32lib/src/stm32f10x_adc.c **** /* JSWSTART bit is reset */ + 946:stm32lib/src/stm32f10x_adc.c **** bitstatus = RESET; + 947:stm32lib/src/stm32f10x_adc.c **** } + 948:stm32lib/src/stm32f10x_adc.c **** + 949:stm32lib/src/stm32f10x_adc.c **** /* Return the JSWSTART bit status */ + 950:stm32lib/src/stm32f10x_adc.c **** return bitstatus; + 951:stm32lib/src/stm32f10x_adc.c **** } + 769 .loc 1 951 0 + 770 0226 C0F34050 ubfx r0, r0, #21, #1 + 771 022a 7047 bx lr + 772 .LFE46: + 774 .align 2 + 775 .global ADC_InjectedChannelConfig + 776 .thumb + 777 .thumb_func + 779 ADC_InjectedChannelConfig: + 780 .LFB47: + 952:stm32lib/src/stm32f10x_adc.c **** + 953:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* + 954:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_InjectedChannelConfig + 955:stm32lib/src/stm32f10x_adc.c **** * Description : Configures for the selected ADC injected channel its corresponding + 956:stm32lib/src/stm32f10x_adc.c **** * rank in the sequencer and its sample time. + 957:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + 958:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel: the ADC channel to configure. + 959:stm32lib/src/stm32f10x_adc.c **** * This parameter can be one of the following values: + 960:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_0: ADC Channel0 selected + 961:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_1: ADC Channel1 selected + 962:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_2: ADC Channel2 selected + 963:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_3: ADC Channel3 selected + 964:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_4: ADC Channel4 selected + 965:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_5: ADC Channel5 selected + 966:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_6: ADC Channel6 selected + 967:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_7: ADC Channel7 selected + 968:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_8: ADC Channel8 selected + 969:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_9: ADC Channel9 selected + 970:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_10: ADC Channel10 selected + 971:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_11: ADC Channel11 selected + 972:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_12: ADC Channel12 selected + 973:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_13: ADC Channel13 selected + 974:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_14: ADC Channel14 selected + 975:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_15: ADC Channel15 selected + 976:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_16: ADC Channel16 selected + 977:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_17: ADC Channel17 selected + 978:stm32lib/src/stm32f10x_adc.c **** * - Rank: The rank in the injected group sequencer. This parameter + 979:stm32lib/src/stm32f10x_adc.c **** * must be between 1 to 4. + 980:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime: The sample time value to be set for the + 981:stm32lib/src/stm32f10x_adc.c **** * selected channel. + 982:stm32lib/src/stm32f10x_adc.c **** * This parameter can be one of the following values: + 983:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles + 984:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles + 985:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles + 986:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles + 987:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles + 988:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles + 989:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles + 990:stm32lib/src/stm32f10x_adc.c **** * - ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles + 991:stm32lib/src/stm32f10x_adc.c **** * Output : None + 992:stm32lib/src/stm32f10x_adc.c **** * Return : None + 993:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ + 994:stm32lib/src/stm32f10x_adc.c **** void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel, u8 Rank, u8 ADC_SampleTime) + 995:stm32lib/src/stm32f10x_adc.c **** { + 781 .loc 1 995 0 + 782 @ args = 0, pretend = 0, frame = 0 + 783 @ frame_needed = 0, uses_anonymous_args = 0 + 784 .LVL61: + 996:stm32lib/src/stm32f10x_adc.c **** u32 tmpreg1 = 0, tmpreg2 = 0, tmpreg3 = 0; + 997:stm32lib/src/stm32f10x_adc.c **** + 998:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ + 999:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); +1000:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_CHANNEL(ADC_Channel)); +1001:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_INJECTED_RANK(Rank)); +1002:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime)); +1003:stm32lib/src/stm32f10x_adc.c **** +1004:stm32lib/src/stm32f10x_adc.c **** /* if ADC_Channel_10 ... ADC_Channel_17 is selected */ +1005:stm32lib/src/stm32f10x_adc.c **** if (ADC_Channel > ADC_Channel_9) + 785 .loc 1 1005 0 + 786 022c 0929 cmp r1, #9 + 787 .loc 1 995 0 + 788 022e 30B5 push {r4, r5, lr} + 789 .LCFI2: + 790 .loc 1 995 0 + 791 0230 8C46 mov ip, r1 + 792 0232 1546 mov r5, r2 + 793 0234 1C46 mov r4, r3 + 794 .loc 1 1005 0 + 795 0236 0DD9 bls .L87 + 796 .LVL62: +1006:stm32lib/src/stm32f10x_adc.c **** { +1007:stm32lib/src/stm32f10x_adc.c **** /* Get the old register value */ +1008:stm32lib/src/stm32f10x_adc.c **** tmpreg1 = ADCx->SMPR1; +1009:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to clear */ +1010:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = SMPR1_SMP_Set << (3*(ADC_Channel - 10)); + 797 .loc 1 1010 0 + 798 0238 0322 movs r2, #3 + 799 023a 02FB0CF2 mul r2, r2, ip +1011:stm32lib/src/stm32f10x_adc.c **** /* Clear the old discontinuous mode channel count */ +1012:stm32lib/src/stm32f10x_adc.c **** tmpreg1 &= ~tmpreg2; + 800 .loc 1 1012 0 + 801 023e 0723 movs r3, #7 + 802 .loc 1 1010 0 + 803 0240 1E3A subs r2, r2, #30 + 804 .loc 1 1012 0 + 805 0242 9340 lsls r3, r3, r2 +1013:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to set */ +1014:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = (u32)ADC_SampleTime << (3*(ADC_Channel - 10)); +1015:stm32lib/src/stm32f10x_adc.c **** /* Set the discontinuous mode channel count */ +1016:stm32lib/src/stm32f10x_adc.c **** tmpreg1 |= tmpreg2; + 806 .loc 1 1016 0 + 807 0244 14FA02F2 lsls r2, r4, r2 + 808 .loc 1 1008 0 + 809 0248 C168 ldr r1, [r0, #12] + 810 .LVL63: + 811 .loc 1 1012 0 + 812 024a 21EA0301 bic r1, r1, r3 + 813 .LVL64: + 814 .loc 1 1016 0 + 815 024e 1143 orrs r1, r1, r2 + 816 .LVL65: +1017:stm32lib/src/stm32f10x_adc.c **** /* Store the new register value */ +1018:stm32lib/src/stm32f10x_adc.c **** ADCx->SMPR1 = tmpreg1; + 817 .loc 1 1018 0 + 818 0250 C160 str r1, [r0, #12] + 819 0252 0BE0 b .L88 + 820 .LVL66: + 821 .L87: +1019:stm32lib/src/stm32f10x_adc.c **** } +1020:stm32lib/src/stm32f10x_adc.c **** else /* ADC_Channel include in ADC_Channel_[0..9] */ +1021:stm32lib/src/stm32f10x_adc.c **** { +1022:stm32lib/src/stm32f10x_adc.c **** /* Get the old register value */ +1023:stm32lib/src/stm32f10x_adc.c **** tmpreg1 = ADCx->SMPR2; +1024:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to clear */ +1025:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel); + 822 .loc 1 1025 0 + 823 0254 0322 movs r2, #3 + 824 0256 02FB0CF2 mul r2, r2, ip +1026:stm32lib/src/stm32f10x_adc.c **** /* Clear the old discontinuous mode channel count */ +1027:stm32lib/src/stm32f10x_adc.c **** tmpreg1 &= ~tmpreg2; + 825 .loc 1 1027 0 + 826 025a 0723 movs r3, #7 + 827 025c 9340 lsls r3, r3, r2 +1028:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to set */ +1029:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = (u32)ADC_SampleTime << (3 * ADC_Channel); +1030:stm32lib/src/stm32f10x_adc.c **** /* Set the discontinuous mode channel count */ +1031:stm32lib/src/stm32f10x_adc.c **** tmpreg1 |= tmpreg2; + 828 .loc 1 1031 0 + 829 025e 14FA02F2 lsls r2, r4, r2 + 830 .loc 1 1023 0 + 831 0262 0169 ldr r1, [r0, #16] + 832 .LVL67: + 833 .loc 1 1027 0 + 834 0264 21EA0301 bic r1, r1, r3 + 835 .LVL68: + 836 .loc 1 1031 0 + 837 0268 1143 orrs r1, r1, r2 + 838 .LVL69: +1032:stm32lib/src/stm32f10x_adc.c **** /* Store the new register value */ +1033:stm32lib/src/stm32f10x_adc.c **** ADCx->SMPR2 = tmpreg1; + 839 .loc 1 1033 0 + 840 026a 0161 str r1, [r0, #16] + 841 .L88: +1034:stm32lib/src/stm32f10x_adc.c **** } +1035:stm32lib/src/stm32f10x_adc.c **** +1036:stm32lib/src/stm32f10x_adc.c **** /* Rank configuration */ +1037:stm32lib/src/stm32f10x_adc.c **** /* Get the old register value */ +1038:stm32lib/src/stm32f10x_adc.c **** tmpreg1 = ADCx->JSQR; + 842 .loc 1 1038 0 + 843 026c 816B ldr r1, [r0, #56] + 844 .LVL70: +1039:stm32lib/src/stm32f10x_adc.c **** /* Get JL value: Number = JL+1 */ +1040:stm32lib/src/stm32f10x_adc.c **** tmpreg3 = (tmpreg1 & JSQR_JL_Set)>> 20; +1041:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to clear: ((Rank-1)+(4-JL-1)) */ +1042:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = JSQR_JSQ_Set << (5 * (u8)((Rank + 3) - (tmpreg3 + 1))); + 845 .loc 1 1042 0 + 846 026e 0522 movs r2, #5 + 847 0270 C1F30153 ubfx r3, r1, #20, #2 + 848 0274 EB1A subs r3, r5, r3 + 849 0276 0233 adds r3, r3, #2 + 850 0278 DBB2 uxtb r3, r3 + 851 027a 5A43 muls r2, r3, r2 +1043:stm32lib/src/stm32f10x_adc.c **** /* Clear the old JSQx bits for the selected rank */ +1044:stm32lib/src/stm32f10x_adc.c **** tmpreg1 &= ~tmpreg2; + 852 .loc 1 1044 0 + 853 027c 1F23 movs r3, #31 + 854 027e 9340 lsls r3, r3, r2 +1045:stm32lib/src/stm32f10x_adc.c **** /* Calculate the mask to set: ((Rank-1)+(4-JL-1)) */ +1046:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = (u32)ADC_Channel << (5 * (u8)((Rank + 3) - (tmpreg3 + 1))); +1047:stm32lib/src/stm32f10x_adc.c **** /* Set the JSQx bits for the selected rank */ +1048:stm32lib/src/stm32f10x_adc.c **** tmpreg1 |= tmpreg2; + 855 .loc 1 1048 0 + 856 0280 0CFA02F2 lsl r2, ip, r2 + 857 .loc 1 1044 0 + 858 0284 21EA0301 bic r1, r1, r3 + 859 .LVL71: + 860 .loc 1 1048 0 + 861 0288 1143 orrs r1, r1, r2 + 862 .LVL72: +1049:stm32lib/src/stm32f10x_adc.c **** /* Store the new register value */ +1050:stm32lib/src/stm32f10x_adc.c **** ADCx->JSQR = tmpreg1; + 863 .loc 1 1050 0 + 864 028a 8163 str r1, [r0, #56] +1051:stm32lib/src/stm32f10x_adc.c **** } + 865 .loc 1 1051 0 + 866 028c 30BD pop {r4, r5, pc} + 867 .LFE47: + 869 028e 00BF .align 2 + 870 .global ADC_InjectedSequencerLengthConfig + 871 .thumb + 872 .thumb_func + 874 ADC_InjectedSequencerLengthConfig: + 875 .LFB48: +1052:stm32lib/src/stm32f10x_adc.c **** +1053:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* +1054:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_InjectedSequencerLengthConfig +1055:stm32lib/src/stm32f10x_adc.c **** * Description : Configures the sequencer length for injected channels +1056:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. +1057:stm32lib/src/stm32f10x_adc.c **** * - Length: The sequencer length. +1058:stm32lib/src/stm32f10x_adc.c **** * This parameter must be a number between 1 to 4. +1059:stm32lib/src/stm32f10x_adc.c **** * Output : None +1060:stm32lib/src/stm32f10x_adc.c **** * Return : None +1061:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ +1062:stm32lib/src/stm32f10x_adc.c **** void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, u8 Length) +1063:stm32lib/src/stm32f10x_adc.c **** { + 876 .loc 1 1063 0 + 877 @ args = 0, pretend = 0, frame = 0 + 878 @ frame_needed = 0, uses_anonymous_args = 0 + 879 @ link register save eliminated. + 880 .LVL73: +1064:stm32lib/src/stm32f10x_adc.c **** u32 tmpreg1 = 0; +1065:stm32lib/src/stm32f10x_adc.c **** u32 tmpreg2 = 0; +1066:stm32lib/src/stm32f10x_adc.c **** +1067:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ +1068:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); +1069:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_INJECTED_LENGTH(Length)); +1070:stm32lib/src/stm32f10x_adc.c **** +1071:stm32lib/src/stm32f10x_adc.c **** /* Get the old register value */ +1072:stm32lib/src/stm32f10x_adc.c **** tmpreg1 = ADCx->JSQR; + 881 .loc 1 1072 0 + 882 0290 836B ldr r3, [r0, #56] + 883 .LVL74: +1073:stm32lib/src/stm32f10x_adc.c **** /* Clear the old injected sequnence lenght JL bits */ +1074:stm32lib/src/stm32f10x_adc.c **** tmpreg1 &= JSQR_JL_Reset; +1075:stm32lib/src/stm32f10x_adc.c **** /* Set the injected sequnence lenght JL bits */ +1076:stm32lib/src/stm32f10x_adc.c **** tmpreg2 = Length - 1; +1077:stm32lib/src/stm32f10x_adc.c **** tmpreg1 |= tmpreg2 << 20; + 884 .loc 1 1077 0 + 885 0292 0139 subs r1, r1, #1 + 886 .LVL75: + 887 .loc 1 1074 0 + 888 0294 23F44013 bic r3, r3, #3145728 + 889 .LVL76: + 890 .loc 1 1077 0 + 891 0298 43EA0153 orr r3, r3, r1, lsl #20 + 892 .LVL77: +1078:stm32lib/src/stm32f10x_adc.c **** /* Store the new register value */ +1079:stm32lib/src/stm32f10x_adc.c **** ADCx->JSQR = tmpreg1; + 893 .loc 1 1079 0 + 894 029c 8363 str r3, [r0, #56] +1080:stm32lib/src/stm32f10x_adc.c **** } + 895 .loc 1 1080 0 + 896 029e 7047 bx lr + 897 .LFE48: + 899 .align 2 + 900 .global ADC_SetInjectedOffset + 901 .thumb + 902 .thumb_func + 904 ADC_SetInjectedOffset: + 905 .LFB49: +1081:stm32lib/src/stm32f10x_adc.c **** +1082:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* +1083:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_SetInjectedOffset +1084:stm32lib/src/stm32f10x_adc.c **** * Description : Set the injected channels conversion value offset +1085:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. +1086:stm32lib/src/stm32f10x_adc.c **** * - ADC_InjectedChannel: the ADC injected channel to set its +1087:stm32lib/src/stm32f10x_adc.c **** * offset. +1088:stm32lib/src/stm32f10x_adc.c **** * This parameter can be one of the following values: +1089:stm32lib/src/stm32f10x_adc.c **** * - ADC_InjectedChannel_1: Injected Channel1 selected +1090:stm32lib/src/stm32f10x_adc.c **** * - ADC_InjectedChannel_2: Injected Channel2 selected +1091:stm32lib/src/stm32f10x_adc.c **** * - ADC_InjectedChannel_3: Injected Channel3 selected +1092:stm32lib/src/stm32f10x_adc.c **** * - ADC_InjectedChannel_4: Injected Channel4 selected +1093:stm32lib/src/stm32f10x_adc.c **** * - Offset: the offset value for the selected ADC injected channel +1094:stm32lib/src/stm32f10x_adc.c **** * This parameter must be a 12bit value. +1095:stm32lib/src/stm32f10x_adc.c **** * Output : None +1096:stm32lib/src/stm32f10x_adc.c **** * Return : None +1097:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ +1098:stm32lib/src/stm32f10x_adc.c **** void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, u8 ADC_InjectedChannel, u16 Offset) +1099:stm32lib/src/stm32f10x_adc.c **** { + 906 .loc 1 1099 0 + 907 @ args = 0, pretend = 0, frame = 8 + 908 @ frame_needed = 0, uses_anonymous_args = 0 + 909 @ link register save eliminated. + 910 .LVL78: + 911 02a0 82B0 sub sp, sp, #8 + 912 .LCFI3: +1100:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ +1101:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); +1102:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel)); +1103:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_OFFSET(Offset)); +1104:stm32lib/src/stm32f10x_adc.c **** +1105:stm32lib/src/stm32f10x_adc.c **** /* Set the selected injected channel data offset */ +1106:stm32lib/src/stm32f10x_adc.c **** *((vu32 *)((*(u32*)&ADCx) + ADC_InjectedChannel)) = (u32)Offset; + 913 .loc 1 1106 0 + 914 02a2 0A50 str r2, [r1, r0] + 915 .LVL79: +1107:stm32lib/src/stm32f10x_adc.c **** } + 916 .loc 1 1107 0 + 917 02a4 02B0 add sp, sp, #8 + 918 02a6 7047 bx lr + 919 .LFE49: + 921 .align 2 + 922 .global ADC_GetInjectedConversionValue + 923 .thumb + 924 .thumb_func + 926 ADC_GetInjectedConversionValue: + 927 .LFB50: +1108:stm32lib/src/stm32f10x_adc.c **** +1109:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* +1110:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_GetInjectedConversionValue +1111:stm32lib/src/stm32f10x_adc.c **** * Description : Returns the ADC injected channel conversion result +1112:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. +1113:stm32lib/src/stm32f10x_adc.c **** * - ADC_InjectedChannel: the converted ADC injected channel. +1114:stm32lib/src/stm32f10x_adc.c **** * This parameter can be one of the following values: +1115:stm32lib/src/stm32f10x_adc.c **** * - ADC_InjectedChannel_1: Injected Channel1 selected +1116:stm32lib/src/stm32f10x_adc.c **** * - ADC_InjectedChannel_2: Injected Channel2 selected +1117:stm32lib/src/stm32f10x_adc.c **** * - ADC_InjectedChannel_3: Injected Channel3 selected +1118:stm32lib/src/stm32f10x_adc.c **** * - ADC_InjectedChannel_4: Injected Channel4 selected +1119:stm32lib/src/stm32f10x_adc.c **** * Output : None +1120:stm32lib/src/stm32f10x_adc.c **** * Return : The Data conversion value. +1121:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ +1122:stm32lib/src/stm32f10x_adc.c **** u16 ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, u8 ADC_InjectedChannel) +1123:stm32lib/src/stm32f10x_adc.c **** { + 928 .loc 1 1123 0 + 929 @ args = 0, pretend = 0, frame = 8 + 930 @ frame_needed = 0, uses_anonymous_args = 0 + 931 @ link register save eliminated. + 932 .LVL80: + 933 02a8 82B0 sub sp, sp, #8 + 934 .LCFI4: + 935 .loc 1 1123 0 + 936 02aa 0190 str r0, [sp, #4] +1124:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ +1125:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); +1126:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel)); +1127:stm32lib/src/stm32f10x_adc.c **** +1128:stm32lib/src/stm32f10x_adc.c **** /* Returns the selected injected channel conversion data value */ +1129:stm32lib/src/stm32f10x_adc.c **** return (u16) (*(vu32*) (((*(u32*)&ADCx) + ADC_InjectedChannel + JDR_Offset))); + 937 .loc 1 1129 0 + 938 02ac 2830 adds r0, r0, #40 + 939 .LVL81: + 940 02ae 4058 ldr r0, [r0, r1] +1130:stm32lib/src/stm32f10x_adc.c **** } + 941 .loc 1 1130 0 + 942 02b0 80B2 uxth r0, r0 + 943 02b2 02B0 add sp, sp, #8 + 944 02b4 7047 bx lr + 945 .LFE50: + 947 02b6 00BF .align 2 + 948 .global ADC_AnalogWatchdogCmd + 949 .thumb + 950 .thumb_func + 952 ADC_AnalogWatchdogCmd: + 953 .LFB51: +1131:stm32lib/src/stm32f10x_adc.c **** +1132:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* +1133:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_AnalogWatchdogCmd +1134:stm32lib/src/stm32f10x_adc.c **** * Description : Enables or disables the analog watchdog on single/all regular +1135:stm32lib/src/stm32f10x_adc.c **** * or injected channels +1136:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. +1137:stm32lib/src/stm32f10x_adc.c **** * - ADC_AnalogWatchdog: the ADC analog watchdog configuration. +1138:stm32lib/src/stm32f10x_adc.c **** * This parameter can be one of the following values: +1139:stm32lib/src/stm32f10x_adc.c **** * - ADC_AnalogWatchdog_SingleRegEnable: Analog watchdog on +1140:stm32lib/src/stm32f10x_adc.c **** * a single regular channel +1141:stm32lib/src/stm32f10x_adc.c **** * - ADC_AnalogWatchdog_SingleInjecEnable: Analog watchdog on +1142:stm32lib/src/stm32f10x_adc.c **** * a single injected channel +1143:stm32lib/src/stm32f10x_adc.c **** * - ADC_AnalogWatchdog_SingleRegOrInjecEnable: Analog +1144:stm32lib/src/stm32f10x_adc.c **** * watchdog on a single regular or injected channel +1145:stm32lib/src/stm32f10x_adc.c **** * - ADC_AnalogWatchdog_AllRegEnable: Analog watchdog on +1146:stm32lib/src/stm32f10x_adc.c **** * all regular channel +1147:stm32lib/src/stm32f10x_adc.c **** * - ADC_AnalogWatchdog_AllInjecEnable: Analog watchdog on +1148:stm32lib/src/stm32f10x_adc.c **** * all injected channel +1149:stm32lib/src/stm32f10x_adc.c **** * - ADC_AnalogWatchdog_AllRegAllInjecEnable: Analog watchdog +1150:stm32lib/src/stm32f10x_adc.c **** * on all regular and injected channels +1151:stm32lib/src/stm32f10x_adc.c **** * - ADC_AnalogWatchdog_None: No channel guarded by the +1152:stm32lib/src/stm32f10x_adc.c **** * analog watchdog +1153:stm32lib/src/stm32f10x_adc.c **** * Output : None +1154:stm32lib/src/stm32f10x_adc.c **** * Return : None +1155:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ +1156:stm32lib/src/stm32f10x_adc.c **** void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, u32 ADC_AnalogWatchdog) +1157:stm32lib/src/stm32f10x_adc.c **** { + 954 .loc 1 1157 0 + 955 @ args = 0, pretend = 0, frame = 0 + 956 @ frame_needed = 0, uses_anonymous_args = 0 + 957 @ link register save eliminated. + 958 .LVL82: +1158:stm32lib/src/stm32f10x_adc.c **** u32 tmpreg = 0; +1159:stm32lib/src/stm32f10x_adc.c **** +1160:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ +1161:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); +1162:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ANALOG_WATCHDOG(ADC_AnalogWatchdog)); +1163:stm32lib/src/stm32f10x_adc.c **** +1164:stm32lib/src/stm32f10x_adc.c **** /* Get the old register value */ +1165:stm32lib/src/stm32f10x_adc.c **** tmpreg = ADCx->CR1; + 959 .loc 1 1165 0 + 960 02b8 4368 ldr r3, [r0, #4] + 961 .LVL83: +1166:stm32lib/src/stm32f10x_adc.c **** /* Clear AWDEN, AWDENJ and AWDSGL bits */ +1167:stm32lib/src/stm32f10x_adc.c **** tmpreg &= CR1_AWDMode_Reset; + 962 .loc 1 1167 0 + 963 02ba 23F44003 bic r3, r3, #12582912 + 964 .LVL84: + 965 02be 23F40073 bic r3, r3, #512 +1168:stm32lib/src/stm32f10x_adc.c **** /* Set the analog watchdog enable mode */ +1169:stm32lib/src/stm32f10x_adc.c **** tmpreg |= ADC_AnalogWatchdog; + 966 .loc 1 1169 0 + 967 02c2 1943 orrs r1, r1, r3 + 968 .LVL85: +1170:stm32lib/src/stm32f10x_adc.c **** /* Store the new register value */ +1171:stm32lib/src/stm32f10x_adc.c **** ADCx->CR1 = tmpreg; + 969 .loc 1 1171 0 + 970 02c4 4160 str r1, [r0, #4] +1172:stm32lib/src/stm32f10x_adc.c **** } + 971 .loc 1 1172 0 + 972 02c6 7047 bx lr + 973 .LFE51: + 975 .align 2 + 976 .global ADC_AnalogWatchdogThresholdsConfig + 977 .thumb + 978 .thumb_func + 980 ADC_AnalogWatchdogThresholdsConfig: + 981 .LFB52: +1173:stm32lib/src/stm32f10x_adc.c **** +1174:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* +1175:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_AnalogWatchdogThresholdsConfig +1176:stm32lib/src/stm32f10x_adc.c **** * Description : Configures the high and low thresholds of the analog watchdog. +1177:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. +1178:stm32lib/src/stm32f10x_adc.c **** * - HighThreshold: the ADC analog watchdog High threshold value. +1179:stm32lib/src/stm32f10x_adc.c **** * This parameter must be a 12bit value. +1180:stm32lib/src/stm32f10x_adc.c **** * - LowThreshold: the ADC analog watchdog Low threshold value. +1181:stm32lib/src/stm32f10x_adc.c **** * This parameter must be a 12bit value. +1182:stm32lib/src/stm32f10x_adc.c **** * Output : None +1183:stm32lib/src/stm32f10x_adc.c **** * Return : None +1184:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ +1185:stm32lib/src/stm32f10x_adc.c **** void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, u16 HighThreshold, +1186:stm32lib/src/stm32f10x_adc.c **** u16 LowThreshold) +1187:stm32lib/src/stm32f10x_adc.c **** { + 982 .loc 1 1187 0 + 983 @ args = 0, pretend = 0, frame = 0 + 984 @ frame_needed = 0, uses_anonymous_args = 0 + 985 @ link register save eliminated. + 986 .LVL86: +1188:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ +1189:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); +1190:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_THRESHOLD(HighThreshold)); +1191:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_THRESHOLD(LowThreshold)); +1192:stm32lib/src/stm32f10x_adc.c **** +1193:stm32lib/src/stm32f10x_adc.c **** /* Set the ADCx high threshold */ +1194:stm32lib/src/stm32f10x_adc.c **** ADCx->HTR = HighThreshold; + 987 .loc 1 1194 0 + 988 02c8 4162 str r1, [r0, #36] +1195:stm32lib/src/stm32f10x_adc.c **** /* Set the ADCx low threshold */ +1196:stm32lib/src/stm32f10x_adc.c **** ADCx->LTR = LowThreshold; + 989 .loc 1 1196 0 + 990 02ca 8262 str r2, [r0, #40] +1197:stm32lib/src/stm32f10x_adc.c **** } + 991 .loc 1 1197 0 + 992 02cc 7047 bx lr + 993 .LFE52: + 995 02ce 00BF .align 2 + 996 .global ADC_AnalogWatchdogSingleChannelConfig + 997 .thumb + 998 .thumb_func + 1000 ADC_AnalogWatchdogSingleChannelConfig: + 1001 .LFB53: +1198:stm32lib/src/stm32f10x_adc.c **** +1199:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* +1200:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_AnalogWatchdogSingleChannelConfig +1201:stm32lib/src/stm32f10x_adc.c **** * Description : Configures the analog watchdog guarded single channel +1202:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. +1203:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel: the ADC channel to configure for the analog +1204:stm32lib/src/stm32f10x_adc.c **** * watchdog. +1205:stm32lib/src/stm32f10x_adc.c **** * This parameter can be one of the following values: +1206:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_0: ADC Channel0 selected +1207:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_1: ADC Channel1 selected +1208:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_2: ADC Channel2 selected +1209:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_3: ADC Channel3 selected +1210:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_4: ADC Channel4 selected +1211:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_5: ADC Channel5 selected +1212:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_6: ADC Channel6 selected +1213:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_7: ADC Channel7 selected +1214:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_8: ADC Channel8 selected +1215:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_9: ADC Channel9 selected +1216:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_10: ADC Channel10 selected +1217:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_11: ADC Channel11 selected +1218:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_12: ADC Channel12 selected +1219:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_13: ADC Channel13 selected +1220:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_14: ADC Channel14 selected +1221:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_15: ADC Channel15 selected +1222:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_16: ADC Channel16 selected +1223:stm32lib/src/stm32f10x_adc.c **** * - ADC_Channel_17: ADC Channel17 selected +1224:stm32lib/src/stm32f10x_adc.c **** * Output : None +1225:stm32lib/src/stm32f10x_adc.c **** * Return : None +1226:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ +1227:stm32lib/src/stm32f10x_adc.c **** void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, u8 ADC_Channel) +1228:stm32lib/src/stm32f10x_adc.c **** { + 1002 .loc 1 1228 0 + 1003 @ args = 0, pretend = 0, frame = 0 + 1004 @ frame_needed = 0, uses_anonymous_args = 0 + 1005 @ link register save eliminated. + 1006 .LVL87: +1229:stm32lib/src/stm32f10x_adc.c **** u32 tmpreg = 0; +1230:stm32lib/src/stm32f10x_adc.c **** +1231:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ +1232:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); +1233:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_CHANNEL(ADC_Channel)); +1234:stm32lib/src/stm32f10x_adc.c **** +1235:stm32lib/src/stm32f10x_adc.c **** /* Get the old register value */ +1236:stm32lib/src/stm32f10x_adc.c **** tmpreg = ADCx->CR1; + 1007 .loc 1 1236 0 + 1008 02d0 4368 ldr r3, [r0, #4] + 1009 .LVL88: +1237:stm32lib/src/stm32f10x_adc.c **** /* Clear the Analog watchdog channel select bits */ +1238:stm32lib/src/stm32f10x_adc.c **** tmpreg &= CR1_AWDCH_Reset; + 1010 .loc 1 1238 0 + 1011 02d2 23F01F03 bic r3, r3, #31 + 1012 .LVL89: +1239:stm32lib/src/stm32f10x_adc.c **** /* Set the Analog watchdog channel */ +1240:stm32lib/src/stm32f10x_adc.c **** tmpreg |= ADC_Channel; + 1013 .loc 1 1240 0 + 1014 02d6 1943 orrs r1, r1, r3 + 1015 .LVL90: +1241:stm32lib/src/stm32f10x_adc.c **** /* Store the new register value */ +1242:stm32lib/src/stm32f10x_adc.c **** ADCx->CR1 = tmpreg; + 1016 .loc 1 1242 0 + 1017 02d8 4160 str r1, [r0, #4] +1243:stm32lib/src/stm32f10x_adc.c **** } + 1018 .loc 1 1243 0 + 1019 02da 7047 bx lr + 1020 .LFE53: + 1022 .align 2 + 1023 .global ADC_TempSensorVrefintCmd + 1024 .thumb + 1025 .thumb_func + 1027 ADC_TempSensorVrefintCmd: + 1028 .LFB54: +1244:stm32lib/src/stm32f10x_adc.c **** +1245:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* +1246:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_TempSensorVrefintCmd +1247:stm32lib/src/stm32f10x_adc.c **** * Description : Enables or disables the temperature sensor and Vrefint channel. +1248:stm32lib/src/stm32f10x_adc.c **** * Input : - NewState: new state of the temperature sensor. +1249:stm32lib/src/stm32f10x_adc.c **** * This parameter can be: ENABLE or DISABLE. +1250:stm32lib/src/stm32f10x_adc.c **** * Output : None +1251:stm32lib/src/stm32f10x_adc.c **** * Return : None +1252:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ +1253:stm32lib/src/stm32f10x_adc.c **** void ADC_TempSensorVrefintCmd(FunctionalState NewState) +1254:stm32lib/src/stm32f10x_adc.c **** { + 1029 .loc 1 1254 0 + 1030 @ args = 0, pretend = 0, frame = 0 + 1031 @ frame_needed = 0, uses_anonymous_args = 0 + 1032 @ link register save eliminated. + 1033 .LVL91: +1255:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ +1256:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); +1257:stm32lib/src/stm32f10x_adc.c **** +1258:stm32lib/src/stm32f10x_adc.c **** if (NewState != DISABLE) + 1034 .loc 1 1258 0 + 1035 02dc 20B1 cbz r0, .L103 +1259:stm32lib/src/stm32f10x_adc.c **** { +1260:stm32lib/src/stm32f10x_adc.c **** /* Enable the temperature sensor and Vrefint channel*/ +1261:stm32lib/src/stm32f10x_adc.c **** ADC1->CR2 |= CR2_TSVREFE_Set; + 1036 .loc 1 1261 0 + 1037 02de 054A ldr r2, .L107 + 1038 02e0 9368 ldr r3, [r2, #8] + 1039 02e2 43F40003 orr r3, r3, #8388608 + 1040 02e6 03E0 b .L106 + 1041 .L103: +1262:stm32lib/src/stm32f10x_adc.c **** } +1263:stm32lib/src/stm32f10x_adc.c **** else +1264:stm32lib/src/stm32f10x_adc.c **** { +1265:stm32lib/src/stm32f10x_adc.c **** /* Disable the temperature sensor and Vrefint channel*/ +1266:stm32lib/src/stm32f10x_adc.c **** ADC1->CR2 &= CR2_TSVREFE_Reset; + 1042 .loc 1 1266 0 + 1043 02e8 024A ldr r2, .L107 + 1044 02ea 9368 ldr r3, [r2, #8] + 1045 02ec 23F40003 bic r3, r3, #8388608 + 1046 .L106: + 1047 02f0 9360 str r3, [r2, #8] +1267:stm32lib/src/stm32f10x_adc.c **** } +1268:stm32lib/src/stm32f10x_adc.c **** } + 1048 .loc 1 1268 0 + 1049 02f2 7047 bx lr + 1050 .L108: + 1051 .align 2 + 1052 .L107: + 1053 02f4 00240140 .word 1073816576 + 1054 .LFE54: + 1056 .align 2 + 1057 .global ADC_GetFlagStatus + 1058 .thumb + 1059 .thumb_func + 1061 ADC_GetFlagStatus: + 1062 .LFB55: +1269:stm32lib/src/stm32f10x_adc.c **** +1270:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* +1271:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_GetFlagStatus +1272:stm32lib/src/stm32f10x_adc.c **** * Description : Checks whether the specified ADC flag is set or not. +1273:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. +1274:stm32lib/src/stm32f10x_adc.c **** * - ADC_FLAG: specifies the flag to check. +1275:stm32lib/src/stm32f10x_adc.c **** * This parameter can be one of the following values: +1276:stm32lib/src/stm32f10x_adc.c **** * - ADC_FLAG_AWD: Analog watchdog flag +1277:stm32lib/src/stm32f10x_adc.c **** * - ADC_FLAG_EOC: End of conversion flag +1278:stm32lib/src/stm32f10x_adc.c **** * - ADC_FLAG_JEOC: End of injected group conversion flag +1279:stm32lib/src/stm32f10x_adc.c **** * - ADC_FLAG_JSTRT: Start of injected group conversion flag +1280:stm32lib/src/stm32f10x_adc.c **** * - ADC_FLAG_STRT: Start of regular group conversion flag +1281:stm32lib/src/stm32f10x_adc.c **** * Output : None +1282:stm32lib/src/stm32f10x_adc.c **** * Return : The new state of ADC_FLAG (SET or RESET). +1283:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ +1284:stm32lib/src/stm32f10x_adc.c **** FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, u8 ADC_FLAG) +1285:stm32lib/src/stm32f10x_adc.c **** { + 1063 .loc 1 1285 0 + 1064 @ args = 0, pretend = 0, frame = 0 + 1065 @ frame_needed = 0, uses_anonymous_args = 0 + 1066 @ link register save eliminated. + 1067 .LVL92: +1286:stm32lib/src/stm32f10x_adc.c **** FlagStatus bitstatus = RESET; +1287:stm32lib/src/stm32f10x_adc.c **** +1288:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ +1289:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); +1290:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_GET_FLAG(ADC_FLAG)); +1291:stm32lib/src/stm32f10x_adc.c **** +1292:stm32lib/src/stm32f10x_adc.c **** /* Check the status of the specified ADC flag */ +1293:stm32lib/src/stm32f10x_adc.c **** if ((ADCx->SR & ADC_FLAG) != (u8)RESET) + 1068 .loc 1 1293 0 + 1069 02f8 0368 ldr r3, [r0, #0] + 1070 02fa 1942 tst r1, r3 +1294:stm32lib/src/stm32f10x_adc.c **** { +1295:stm32lib/src/stm32f10x_adc.c **** /* ADC_FLAG is set */ +1296:stm32lib/src/stm32f10x_adc.c **** bitstatus = SET; +1297:stm32lib/src/stm32f10x_adc.c **** } +1298:stm32lib/src/stm32f10x_adc.c **** else +1299:stm32lib/src/stm32f10x_adc.c **** { +1300:stm32lib/src/stm32f10x_adc.c **** /* ADC_FLAG is reset */ +1301:stm32lib/src/stm32f10x_adc.c **** bitstatus = RESET; +1302:stm32lib/src/stm32f10x_adc.c **** } +1303:stm32lib/src/stm32f10x_adc.c **** +1304:stm32lib/src/stm32f10x_adc.c **** /* Return the ADC_FLAG status */ +1305:stm32lib/src/stm32f10x_adc.c **** return bitstatus; +1306:stm32lib/src/stm32f10x_adc.c **** } + 1071 .loc 1 1306 0 + 1072 02fc 0CBF ite eq + 1073 02fe 0020 moveq r0, #0 + 1074 0300 0120 movne r0, #1 + 1075 .LVL93: + 1076 0302 7047 bx lr + 1077 .LFE55: + 1079 .align 2 + 1080 .global ADC_ClearFlag + 1081 .thumb + 1082 .thumb_func + 1084 ADC_ClearFlag: + 1085 .LFB56: +1307:stm32lib/src/stm32f10x_adc.c **** +1308:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* +1309:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_ClearFlag +1310:stm32lib/src/stm32f10x_adc.c **** * Description : Clears the ADCx's pending flags. +1311:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. +1312:stm32lib/src/stm32f10x_adc.c **** * - ADC_FLAG: specifies the flag to clear. +1313:stm32lib/src/stm32f10x_adc.c **** * This parameter can be any combination of the following values: +1314:stm32lib/src/stm32f10x_adc.c **** * - ADC_FLAG_AWD: Analog watchdog flag +1315:stm32lib/src/stm32f10x_adc.c **** * - ADC_FLAG_EOC: End of conversion flag +1316:stm32lib/src/stm32f10x_adc.c **** * - ADC_FLAG_JEOC: End of injected group conversion flag +1317:stm32lib/src/stm32f10x_adc.c **** * - ADC_FLAG_JSTRT: Start of injected group conversion flag +1318:stm32lib/src/stm32f10x_adc.c **** * - ADC_FLAG_STRT: Start of regular group conversion flag +1319:stm32lib/src/stm32f10x_adc.c **** * Output : None +1320:stm32lib/src/stm32f10x_adc.c **** * Return : None +1321:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ +1322:stm32lib/src/stm32f10x_adc.c **** void ADC_ClearFlag(ADC_TypeDef* ADCx, u8 ADC_FLAG) +1323:stm32lib/src/stm32f10x_adc.c **** { + 1086 .loc 1 1323 0 + 1087 @ args = 0, pretend = 0, frame = 0 + 1088 @ frame_needed = 0, uses_anonymous_args = 0 + 1089 @ link register save eliminated. + 1090 .LVL94: +1324:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ +1325:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); +1326:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_CLEAR_FLAG(ADC_FLAG)); +1327:stm32lib/src/stm32f10x_adc.c **** +1328:stm32lib/src/stm32f10x_adc.c **** /* Clear the selected ADC flags */ +1329:stm32lib/src/stm32f10x_adc.c **** ADCx->SR = ~(u32)ADC_FLAG; + 1091 .loc 1 1329 0 + 1092 0304 C943 mvns r1, r1 + 1093 .LVL95: + 1094 0306 0160 str r1, [r0, #0] +1330:stm32lib/src/stm32f10x_adc.c **** } + 1095 .loc 1 1330 0 + 1096 0308 7047 bx lr + 1097 .LFE56: + 1099 030a 00BF .align 2 + 1100 .global ADC_GetITStatus + 1101 .thumb + 1102 .thumb_func + 1104 ADC_GetITStatus: + 1105 .LFB57: +1331:stm32lib/src/stm32f10x_adc.c **** +1332:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* +1333:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_GetITStatus +1334:stm32lib/src/stm32f10x_adc.c **** * Description : Checks whether the specified ADC interrupt has occurred or not. +1335:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. +1336:stm32lib/src/stm32f10x_adc.c **** * - ADC_IT: specifies the ADC interrupt source to check. +1337:stm32lib/src/stm32f10x_adc.c **** * This parameter can be one of the following values: +1338:stm32lib/src/stm32f10x_adc.c **** * - ADC_IT_EOC: End of conversion interrupt mask +1339:stm32lib/src/stm32f10x_adc.c **** * - ADC_IT_AWD: Analog watchdog interrupt mask +1340:stm32lib/src/stm32f10x_adc.c **** * - ADC_IT_JEOC: End of injected conversion interrupt mask +1341:stm32lib/src/stm32f10x_adc.c **** * Output : None +1342:stm32lib/src/stm32f10x_adc.c **** * Return : The new state of ADC_IT (SET or RESET). +1343:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ +1344:stm32lib/src/stm32f10x_adc.c **** ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, u16 ADC_IT) +1345:stm32lib/src/stm32f10x_adc.c **** { + 1106 .loc 1 1345 0 + 1107 @ args = 0, pretend = 0, frame = 0 + 1108 @ frame_needed = 0, uses_anonymous_args = 0 + 1109 @ link register save eliminated. + 1110 .LVL96: +1346:stm32lib/src/stm32f10x_adc.c **** ITStatus bitstatus = RESET; +1347:stm32lib/src/stm32f10x_adc.c **** u32 itmask = 0, enablestatus = 0; +1348:stm32lib/src/stm32f10x_adc.c **** +1349:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ +1350:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); +1351:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_GET_IT(ADC_IT)); +1352:stm32lib/src/stm32f10x_adc.c **** +1353:stm32lib/src/stm32f10x_adc.c **** /* Get the ADC IT index */ +1354:stm32lib/src/stm32f10x_adc.c **** itmask = ADC_IT >> 8; +1355:stm32lib/src/stm32f10x_adc.c **** +1356:stm32lib/src/stm32f10x_adc.c **** /* Get the ADC_IT enable bit status */ +1357:stm32lib/src/stm32f10x_adc.c **** enablestatus = (ADCx->CR1 & (u8)ADC_IT) ; + 1111 .loc 1 1357 0 + 1112 030c 4268 ldr r2, [r0, #4] +1358:stm32lib/src/stm32f10x_adc.c **** +1359:stm32lib/src/stm32f10x_adc.c **** /* Check the status of the specified ADC interrupt */ +1360:stm32lib/src/stm32f10x_adc.c **** if (((ADCx->SR & itmask) != (u32)RESET) && enablestatus) + 1113 .loc 1 1360 0 + 1114 030e 0368 ldr r3, [r0, #0] + 1115 0310 13EA1120 ands r0, r3, r1, lsr #8 + 1116 .LVL97: + 1117 0314 04D0 beq .L115 + 1118 0316 CBB2 uxtb r3, r1 + 1119 .LVL98: + 1120 0318 1342 tst r3, r2 + 1121 031a 0CBF ite eq + 1122 031c 0020 moveq r0, #0 + 1123 031e 0120 movne r0, #1 + 1124 .LVL99: + 1125 .L115: + 1126 .LVL100: +1361:stm32lib/src/stm32f10x_adc.c **** { +1362:stm32lib/src/stm32f10x_adc.c **** /* ADC_IT is set */ +1363:stm32lib/src/stm32f10x_adc.c **** bitstatus = SET; +1364:stm32lib/src/stm32f10x_adc.c **** } +1365:stm32lib/src/stm32f10x_adc.c **** else +1366:stm32lib/src/stm32f10x_adc.c **** { +1367:stm32lib/src/stm32f10x_adc.c **** /* ADC_IT is reset */ +1368:stm32lib/src/stm32f10x_adc.c **** bitstatus = RESET; +1369:stm32lib/src/stm32f10x_adc.c **** } +1370:stm32lib/src/stm32f10x_adc.c **** +1371:stm32lib/src/stm32f10x_adc.c **** /* Return the ADC_IT status */ +1372:stm32lib/src/stm32f10x_adc.c **** return bitstatus; +1373:stm32lib/src/stm32f10x_adc.c **** } + 1127 .loc 1 1373 0 + 1128 0320 7047 bx lr + 1129 .LFE57: + 1131 0322 00BF .align 2 + 1132 .global ADC_ClearITPendingBit + 1133 .thumb + 1134 .thumb_func + 1136 ADC_ClearITPendingBit: + 1137 .LFB58: +1374:stm32lib/src/stm32f10x_adc.c **** +1375:stm32lib/src/stm32f10x_adc.c **** /******************************************************************************* +1376:stm32lib/src/stm32f10x_adc.c **** * Function Name : ADC_ClearITPendingBit +1377:stm32lib/src/stm32f10x_adc.c **** * Description : Clears the ADCx’s interrupt pending bits. +1378:stm32lib/src/stm32f10x_adc.c **** * Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. +1379:stm32lib/src/stm32f10x_adc.c **** * - ADC_IT: specifies the ADC interrupt pending bit to clear. +1380:stm32lib/src/stm32f10x_adc.c **** * This parameter can be any combination of the following values: +1381:stm32lib/src/stm32f10x_adc.c **** * - ADC_IT_EOC: End of conversion interrupt mask +1382:stm32lib/src/stm32f10x_adc.c **** * - ADC_IT_AWD: Analog watchdog interrupt mask +1383:stm32lib/src/stm32f10x_adc.c **** * - ADC_IT_JEOC: End of injected conversion interrupt mask +1384:stm32lib/src/stm32f10x_adc.c **** * Output : None +1385:stm32lib/src/stm32f10x_adc.c **** * Return : None +1386:stm32lib/src/stm32f10x_adc.c **** *******************************************************************************/ +1387:stm32lib/src/stm32f10x_adc.c **** void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, u16 ADC_IT) +1388:stm32lib/src/stm32f10x_adc.c **** { + 1138 .loc 1 1388 0 + 1139 @ args = 0, pretend = 0, frame = 0 + 1140 @ frame_needed = 0, uses_anonymous_args = 0 + 1141 @ link register save eliminated. + 1142 .LVL101: +1389:stm32lib/src/stm32f10x_adc.c **** u8 itmask = 0; +1390:stm32lib/src/stm32f10x_adc.c **** +1391:stm32lib/src/stm32f10x_adc.c **** /* Check the parameters */ +1392:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_ALL_PERIPH(ADCx)); +1393:stm32lib/src/stm32f10x_adc.c **** assert_param(IS_ADC_IT(ADC_IT)); +1394:stm32lib/src/stm32f10x_adc.c **** +1395:stm32lib/src/stm32f10x_adc.c **** /* Get the ADC IT index */ +1396:stm32lib/src/stm32f10x_adc.c **** itmask = (u8)(ADC_IT >> 8); +1397:stm32lib/src/stm32f10x_adc.c **** +1398:stm32lib/src/stm32f10x_adc.c **** /* Clear the selected ADC interrupt pending bits */ +1399:stm32lib/src/stm32f10x_adc.c **** ADCx->SR = ~(u32)itmask; + 1143 .loc 1 1399 0 + 1144 0324 6FEA1121 mvn r1, r1, lsr #8 + 1145 .LVL102: + 1146 0328 0160 str r1, [r0, #0] +1400:stm32lib/src/stm32f10x_adc.c **** } + 1147 .loc 1 1400 0 + 1148 032a 7047 bx lr + 1149 .LFE58: + 1151 .align 2 + 1152 .global ADC_DeInit + 1153 .thumb + 1154 .thumb_func + 1156 ADC_DeInit: + 1157 .LFB23: + 1158 .loc 1 131 0 + 1159 @ args = 0, pretend = 0, frame = 8 + 1160 @ frame_needed = 0, uses_anonymous_args = 0 + 1161 .LVL103: + 1162 032c 07B5 push {r0, r1, r2, lr} + 1163 .LCFI5: + 1164 .LVL104: + 1165 .loc 1 135 0 + 1166 032e 134B ldr r3, .L126 + 1167 .loc 1 131 0 + 1168 0330 0190 str r0, [sp, #4] + 1169 .LVL105: + 1170 .loc 1 135 0 + 1171 0332 9842 cmp r0, r3 + 1172 .LVL106: + 1173 0334 0FD0 beq .L122 + 1174 0336 03F5A053 add r3, r3, #5120 + 1175 033a 9842 cmp r0, r3 + 1176 033c 13D0 beq .L123 + 1177 033e A3F5C053 sub r3, r3, #6144 + 1178 0342 9842 cmp r0, r3 + 1179 0344 19D1 bne .L124 + 1180 .loc 1 139 0 + 1181 0346 4FF40070 mov r0, #512 + 1182 034a 0121 movs r1, #1 + 1183 034c FFF7FEFF bl RCC_APB2PeriphResetCmd + 1184 .loc 1 141 0 + 1185 0350 4FF40070 mov r0, #512 + 1186 0354 0EE0 b .L125 + 1187 .L122: + 1188 .loc 1 146 0 + 1189 0356 4FF48060 mov r0, #1024 + 1190 035a 0121 movs r1, #1 + 1191 035c FFF7FEFF bl RCC_APB2PeriphResetCmd + 1192 .loc 1 148 0 + 1193 0360 4FF48060 mov r0, #1024 + 1194 0364 06E0 b .L125 + 1195 .L123: + 1196 .loc 1 153 0 + 1197 0366 4FF40040 mov r0, #32768 + 1198 036a 0121 movs r1, #1 + 1199 036c FFF7FEFF bl RCC_APB2PeriphResetCmd + 1200 .loc 1 155 0 + 1201 0370 4FF40040 mov r0, #32768 + 1202 .L125: + 1203 0374 0021 movs r1, #0 + 1204 0376 FFF7FEFF bl RCC_APB2PeriphResetCmd + 1205 .L124: + 1206 .loc 1 161 0 + 1207 037a 0EBD pop {r1, r2, r3, pc} + 1208 .L127: + 1209 .align 2 + 1210 .L126: + 1211 037c 00280140 .word 1073817600 + 1212 .LFE23: + 1566 .Letext0: +DEFINED SYMBOLS + *ABS*:00000000 stm32f10x_adc.c + /tmp/cc8JynLs.s:22 .text:00000000 $t + /tmp/cc8JynLs.s:27 .text:00000000 ADC_Init + /tmp/cc8JynLs.s:90 .text:00000044 $d + /tmp/cc8JynLs.s:93 .text:00000048 $t + /tmp/cc8JynLs.s:98 .text:00000048 ADC_StructInit + /tmp/cc8JynLs.s:128 .text:0000005c ADC_Cmd + /tmp/cc8JynLs.s:156 .text:00000070 ADC_DMACmd + /tmp/cc8JynLs.s:184 .text:00000084 ADC_ITConfig + /tmp/cc8JynLs.s:215 .text:0000009c ADC_ResetCalibration + /tmp/cc8JynLs.s:235 .text:000000a8 ADC_GetResetCalibrationStatus + /tmp/cc8JynLs.s:255 .text:000000b0 ADC_StartCalibration + /tmp/cc8JynLs.s:275 .text:000000bc ADC_GetCalibrationStatus + /tmp/cc8JynLs.s:295 .text:000000c4 ADC_SoftwareStartConvCmd + /tmp/cc8JynLs.s:323 .text:000000d8 ADC_GetSoftwareStartConvStatus + /tmp/cc8JynLs.s:343 .text:000000e0 ADC_DiscModeChannelCountConfig + /tmp/cc8JynLs.s:373 .text:000000f0 ADC_DiscModeCmd + /tmp/cc8JynLs.s:401 .text:00000104 ADC_RegularChannelConfig + /tmp/cc8JynLs.s:550 .text:000001a0 ADC_ExternalTrigConvCmd + /tmp/cc8JynLs.s:578 .text:000001b4 ADC_GetConversionValue + /tmp/cc8JynLs.s:598 .text:000001bc ADC_GetDualModeConversionValue + /tmp/cc8JynLs.s:612 .text:000001c4 $d + /tmp/cc8JynLs.s:615 .text:000001c8 $t + /tmp/cc8JynLs.s:620 .text:000001c8 ADC_AutoInjectedConvCmd + /tmp/cc8JynLs.s:648 .text:000001dc ADC_InjectedDiscModeCmd + /tmp/cc8JynLs.s:676 .text:000001f0 ADC_ExternalTrigInjectedConvConfig + /tmp/cc8JynLs.s:703 .text:000001fc ADC_ExternalTrigInjectedConvCmd + /tmp/cc8JynLs.s:731 .text:00000210 ADC_SoftwareStartInjectedConvCmd + /tmp/cc8JynLs.s:759 .text:00000224 ADC_GetSoftwareStartInjectedConvCmdStatus + /tmp/cc8JynLs.s:779 .text:0000022c ADC_InjectedChannelConfig + /tmp/cc8JynLs.s:874 .text:00000290 ADC_InjectedSequencerLengthConfig + /tmp/cc8JynLs.s:904 .text:000002a0 ADC_SetInjectedOffset + /tmp/cc8JynLs.s:926 .text:000002a8 ADC_GetInjectedConversionValue + /tmp/cc8JynLs.s:952 .text:000002b8 ADC_AnalogWatchdogCmd + /tmp/cc8JynLs.s:980 .text:000002c8 ADC_AnalogWatchdogThresholdsConfig + /tmp/cc8JynLs.s:1000 .text:000002d0 ADC_AnalogWatchdogSingleChannelConfig + /tmp/cc8JynLs.s:1027 .text:000002dc ADC_TempSensorVrefintCmd + /tmp/cc8JynLs.s:1053 .text:000002f4 $d + /tmp/cc8JynLs.s:1056 .text:000002f8 $t + /tmp/cc8JynLs.s:1061 .text:000002f8 ADC_GetFlagStatus + /tmp/cc8JynLs.s:1084 .text:00000304 ADC_ClearFlag + /tmp/cc8JynLs.s:1104 .text:0000030c ADC_GetITStatus + /tmp/cc8JynLs.s:1136 .text:00000324 ADC_ClearITPendingBit + /tmp/cc8JynLs.s:1156 .text:0000032c ADC_DeInit + /tmp/cc8JynLs.s:1211 .text:0000037c $d + +UNDEFINED SYMBOLS +RCC_APB2PeriphResetCmd diff --git a/src/stm32lib/src/stm32f10x_bkp.c b/src/stm32lib/src/stm32f10x_bkp.c new file mode 100644 index 0000000..a6d3825 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_bkp.c @@ -0,0 +1,272 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_bkp.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the BKP firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_bkp.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ------------ BKP registers bit address in the alias region ----------- */
+#define BKP_OFFSET (BKP_BASE - PERIPH_BASE)
+
+/* --- CR Register ---*/
+/* Alias word address of TPAL bit */
+#define CR_OFFSET (BKP_OFFSET + 0x30)
+#define TPAL_BitNumber 0x01
+#define CR_TPAL_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPAL_BitNumber * 4))
+
+/* Alias word address of TPE bit */
+#define TPE_BitNumber 0x00
+#define CR_TPE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPE_BitNumber * 4))
+
+/* --- CSR Register ---*/
+/* Alias word address of TPIE bit */
+#define CSR_OFFSET (BKP_OFFSET + 0x34)
+#define TPIE_BitNumber 0x02
+#define CSR_TPIE_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TPIE_BitNumber * 4))
+
+/* Alias word address of TIF bit */
+#define TIF_BitNumber 0x09
+#define CSR_TIF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TIF_BitNumber * 4))
+
+/* Alias word address of TEF bit */
+#define TEF_BitNumber 0x08
+#define CSR_TEF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TEF_BitNumber * 4))
+
+
+/* ---------------------- BKP registers bit mask ------------------------ */
+/* RTCCR register bit mask */
+#define RTCCR_CAL_Mask ((u16)0xFF80)
+#define RTCCR_Mask ((u16)0xFC7F)
+
+/* CSR register bit mask */
+#define CSR_CTE_Set ((u16)0x0001)
+#define CSR_CTI_Set ((u16)0x0002)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : BKP_DeInit
+* Description : Deinitializes the BKP peripheral registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_DeInit(void)
+{
+ RCC_BackupResetCmd(ENABLE);
+ RCC_BackupResetCmd(DISABLE);
+}
+
+/*******************************************************************************
+* Function Name : BKP_TamperPinLevelConfig
+* Description : Configures the Tamper Pin active level.
+* Input : - BKP_TamperPinLevel: specifies the Tamper Pin active level.
+* This parameter can be one of the following values:
+* - BKP_TamperPinLevel_High: Tamper pin active on high level
+* - BKP_TamperPinLevel_Low: Tamper pin active on low level
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_TamperPinLevelConfig(u16 BKP_TamperPinLevel)
+{
+ /* Check the parameters */
+ assert_param(IS_BKP_TAMPER_PIN_LEVEL(BKP_TamperPinLevel));
+
+ *(vu32 *) CR_TPAL_BB = BKP_TamperPinLevel;
+}
+
+/*******************************************************************************
+* Function Name : BKP_TamperPinCmd
+* Description : Enables or disables the Tamper Pin activation.
+* Input : - NewState: new state of the Tamper Pin activation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_TamperPinCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CR_TPE_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : BKP_ITConfig
+* Description : Enables or disables the Tamper Pin Interrupt.
+* Input : - NewState: new state of the Tamper Pin Interrupt.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_ITConfig(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CSR_TPIE_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : BKP_RTCOutputConfig
+* Description : Select the RTC output source to output on the Tamper pin.
+* Input : - BKP_RTCOutputSource: specifies the RTC output source.
+* This parameter can be one of the following values:
+* - BKP_RTCOutputSource_None: no RTC output on the Tamper pin.
+* - BKP_RTCOutputSource_CalibClock: output the RTC clock
+* with frequency divided by 64 on the Tamper pin.
+* - BKP_RTCOutputSource_Alarm: output the RTC Alarm pulse
+* signal on the Tamper pin.
+* - BKP_RTCOutputSource_Second: output the RTC Second pulse
+* signal on the Tamper pin.
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_RTCOutputConfig(u16 BKP_RTCOutputSource)
+{
+ u16 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_BKP_RTC_OUTPUT_SOURCE(BKP_RTCOutputSource));
+
+ tmpreg = BKP->RTCCR;
+
+ /* Clear CCO, ASOE and ASOS bits */
+ tmpreg &= RTCCR_Mask;
+
+ /* Set CCO, ASOE and ASOS bits according to BKP_RTCOutputSource value */
+ tmpreg |= BKP_RTCOutputSource;
+
+ /* Store the new value */
+ BKP->RTCCR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : BKP_SetRTCCalibrationValue
+* Description : Sets RTC Clock Calibration value.
+* Input : - CalibrationValue: specifies the RTC Clock Calibration value.
+* This parameter must be a number between 0 and 0x7F.
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_SetRTCCalibrationValue(u8 CalibrationValue)
+{
+ u16 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_BKP_CALIBRATION_VALUE(CalibrationValue));
+
+ tmpreg = BKP->RTCCR;
+
+ /* Clear CAL[6:0] bits */
+ tmpreg &= RTCCR_CAL_Mask;
+
+ /* Set CAL[6:0] bits according to CalibrationValue value */
+ tmpreg |= CalibrationValue;
+
+ /* Store the new value */
+ BKP->RTCCR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : BKP_WriteBackupRegister
+* Description : Writes user data to the specified Data Backup Register.
+* Input : - BKP_DR: specifies the Data Backup Register.
+* This parameter can be BKP_DRx where x:[1, 42]
+* - Data: data to write
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_WriteBackupRegister(u16 BKP_DR, u16 Data)
+{
+ /* Check the parameters */
+ assert_param(IS_BKP_DR(BKP_DR));
+
+ *(vu16 *) (BKP_BASE + BKP_DR) = Data;
+}
+
+/*******************************************************************************
+* Function Name : BKP_ReadBackupRegister
+* Description : Reads data from the specified Data Backup Register.
+* Input : - BKP_DR: specifies the Data Backup Register.
+* This parameter can be BKP_DRx where x:[1, 42]
+* Output : None
+* Return : The content of the specified Data Backup Register
+*******************************************************************************/
+u16 BKP_ReadBackupRegister(u16 BKP_DR)
+{
+ /* Check the parameters */
+ assert_param(IS_BKP_DR(BKP_DR));
+
+ return (*(vu16 *) (BKP_BASE + BKP_DR));
+}
+
+/*******************************************************************************
+* Function Name : BKP_GetFlagStatus
+* Description : Checks whether the Tamper Pin Event flag is set or not.
+* Input : None
+* Output : None
+* Return : The new state of the Tamper Pin Event flag (SET or RESET).
+*******************************************************************************/
+FlagStatus BKP_GetFlagStatus(void)
+{
+ return (FlagStatus)(*(vu32 *) CSR_TEF_BB);
+}
+
+/*******************************************************************************
+* Function Name : BKP_ClearFlag
+* Description : Clears Tamper Pin Event pending flag.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_ClearFlag(void)
+{
+ /* Set CTE bit to clear Tamper Pin Event flag */
+ BKP->CSR |= CSR_CTE_Set;
+}
+
+/*******************************************************************************
+* Function Name : BKP_GetITStatus
+* Description : Checks whether the Tamper Pin Interrupt has occurred or not.
+* Input : None
+* Output : None
+* Return : The new state of the Tamper Pin Interrupt (SET or RESET).
+*******************************************************************************/
+ITStatus BKP_GetITStatus(void)
+{
+ return (ITStatus)(*(vu32 *) CSR_TIF_BB);
+}
+
+/*******************************************************************************
+* Function Name : BKP_ClearITPendingBit
+* Description : Clears Tamper Pin Interrupt pending bit.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void BKP_ClearITPendingBit(void)
+{
+ /* Set CTI bit to clear Tamper Pin Interrupt pending bit */
+ BKP->CSR |= CSR_CTI_Set;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_can.c b/src/stm32lib/src/stm32f10x_can.c new file mode 100644 index 0000000..afb472d --- /dev/null +++ b/src/stm32lib/src/stm32f10x_can.c @@ -0,0 +1,907 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_can.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the CAN firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_can.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+
+/* Private define ------------------------------------------------------------*/
+/* CAN Master Control Register bits */
+#define CAN_MCR_INRQ ((u32)0x00000001) /* Initialization request */
+#define CAN_MCR_SLEEP ((u32)0x00000002) /* Sleep mode request */
+#define CAN_MCR_TXFP ((u32)0x00000004) /* Transmit FIFO priority */
+#define CAN_MCR_RFLM ((u32)0x00000008) /* Receive FIFO locked mode */
+#define CAN_MCR_NART ((u32)0x00000010) /* No automatic retransmission */
+#define CAN_MCR_AWUM ((u32)0x00000020) /* Automatic wake up mode */
+#define CAN_MCR_ABOM ((u32)0x00000040) /* Automatic bus-off management */
+#define CAN_MCR_TTCM ((u32)0x00000080) /* time triggered communication */
+
+/* CAN Master Status Register bits */
+#define CAN_MSR_INAK ((u32)0x00000001) /* Initialization acknowledge */
+#define CAN_MSR_WKUI ((u32)0x00000008) /* Wake-up interrupt */
+#define CAN_MSR_SLAKI ((u32)0x00000010) /* Sleep acknowledge interrupt */
+
+/* CAN Transmit Status Register bits */
+#define CAN_TSR_RQCP0 ((u32)0x00000001) /* Request completed mailbox0 */
+#define CAN_TSR_TXOK0 ((u32)0x00000002) /* Transmission OK of mailbox0 */
+#define CAN_TSR_ABRQ0 ((u32)0x00000080) /* Abort request for mailbox0 */
+#define CAN_TSR_RQCP1 ((u32)0x00000100) /* Request completed mailbox1 */
+#define CAN_TSR_TXOK1 ((u32)0x00000200) /* Transmission OK of mailbox1 */
+#define CAN_TSR_ABRQ1 ((u32)0x00008000) /* Abort request for mailbox1 */
+#define CAN_TSR_RQCP2 ((u32)0x00010000) /* Request completed mailbox2 */
+#define CAN_TSR_TXOK2 ((u32)0x00020000) /* Transmission OK of mailbox2 */
+#define CAN_TSR_ABRQ2 ((u32)0x00800000) /* Abort request for mailbox2 */
+#define CAN_TSR_TME0 ((u32)0x04000000) /* Transmit mailbox 0 empty */
+#define CAN_TSR_TME1 ((u32)0x08000000) /* Transmit mailbox 1 empty */
+#define CAN_TSR_TME2 ((u32)0x10000000) /* Transmit mailbox 2 empty */
+
+/* CAN Receive FIFO 0 Register bits */
+#define CAN_RF0R_FULL0 ((u32)0x00000008) /* FIFO 0 full */
+#define CAN_RF0R_FOVR0 ((u32)0x00000010) /* FIFO 0 overrun */
+#define CAN_RF0R_RFOM0 ((u32)0x00000020) /* Release FIFO 0 output mailbox */
+
+/* CAN Receive FIFO 1 Register bits */
+#define CAN_RF1R_FULL1 ((u32)0x00000008) /* FIFO 1 full */
+#define CAN_RF1R_FOVR1 ((u32)0x00000010) /* FIFO 1 overrun */
+#define CAN_RF1R_RFOM1 ((u32)0x00000020) /* Release FIFO 1 output mailbox */
+
+/* CAN Error Status Register bits */
+#define CAN_ESR_EWGF ((u32)0x00000001) /* Error warning flag */
+#define CAN_ESR_EPVF ((u32)0x00000002) /* Error passive flag */
+#define CAN_ESR_BOFF ((u32)0x00000004) /* Bus-off flag */
+
+/* CAN Mailbox Transmit Request */
+#define CAN_TMIDxR_TXRQ ((u32)0x00000001) /* Transmit mailbox request */
+
+/* CAN Filter Master Register bits */
+#define CAN_FMR_FINIT ((u32)0x00000001) /* Filter init mode */
+
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+static ITStatus CheckITStatus(u32 CAN_Reg, u32 It_Bit);
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : CAN_DeInit
+* Description : Deinitializes the CAN peripheral registers to their default
+* reset values.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_DeInit(void)
+{
+ /* Enable CAN reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN, ENABLE);
+ /* Release CAN from reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN, DISABLE);
+}
+
+/*******************************************************************************
+* Function Name : CAN_Init
+* Description : Initializes the CAN peripheral according to the specified
+* parameters in the CAN_InitStruct.
+* Input : CAN_InitStruct: pointer to a CAN_InitTypeDef structure that
+ contains the configuration information for the CAN peripheral.
+* Output : None.
+* Return : Constant indicates initialization succeed which will be
+* CANINITFAILED or CANINITOK.
+*******************************************************************************/
+u8 CAN_Init(CAN_InitTypeDef* CAN_InitStruct)
+{
+ u8 InitStatus = 0;
+ u16 WaitAck = 0;
+
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TTCM));
+ assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_ABOM));
+ assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_AWUM));
+ assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_NART));
+ assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_RFLM));
+ assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TXFP));
+ assert_param(IS_CAN_MODE(CAN_InitStruct->CAN_Mode));
+ assert_param(IS_CAN_SJW(CAN_InitStruct->CAN_SJW));
+ assert_param(IS_CAN_BS1(CAN_InitStruct->CAN_BS1));
+ assert_param(IS_CAN_BS2(CAN_InitStruct->CAN_BS2));
+ assert_param(IS_CAN_PRESCALER(CAN_InitStruct->CAN_Prescaler));
+
+ /* Request initialisation */
+ CAN->MCR = CAN_MCR_INRQ;
+
+ /* ...and check acknowledged */
+ if ((CAN->MSR & CAN_MSR_INAK) == 0)
+ {
+ InitStatus = CANINITFAILED;
+ }
+ else
+ {
+ /* Set the time triggered communication mode */
+ if (CAN_InitStruct->CAN_TTCM == ENABLE)
+ {
+ CAN->MCR |= CAN_MCR_TTCM;
+ }
+ else
+ {
+ CAN->MCR &= ~CAN_MCR_TTCM;
+ }
+
+ /* Set the automatic bus-off management */
+ if (CAN_InitStruct->CAN_ABOM == ENABLE)
+ {
+ CAN->MCR |= CAN_MCR_ABOM;
+ }
+ else
+ {
+ CAN->MCR &= ~CAN_MCR_ABOM;
+ }
+
+ /* Set the automatic wake-up mode */
+ if (CAN_InitStruct->CAN_AWUM == ENABLE)
+ {
+ CAN->MCR |= CAN_MCR_AWUM;
+ }
+ else
+ {
+ CAN->MCR &= ~CAN_MCR_AWUM;
+ }
+
+ /* Set the no automatic retransmission */
+ if (CAN_InitStruct->CAN_NART == ENABLE)
+ {
+ CAN->MCR |= CAN_MCR_NART;
+ }
+ else
+ {
+ CAN->MCR &= ~CAN_MCR_NART;
+ }
+
+ /* Set the receive FIFO locked mode */
+ if (CAN_InitStruct->CAN_RFLM == ENABLE)
+ {
+ CAN->MCR |= CAN_MCR_RFLM;
+ }
+ else
+ {
+ CAN->MCR &= ~CAN_MCR_RFLM;
+ }
+
+ /* Set the transmit FIFO priority */
+ if (CAN_InitStruct->CAN_TXFP == ENABLE)
+ {
+ CAN->MCR |= CAN_MCR_TXFP;
+ }
+ else
+ {
+ CAN->MCR &= ~CAN_MCR_TXFP;
+ }
+
+ /* Set the bit timing register */
+ CAN->BTR = (u32)((u32)CAN_InitStruct->CAN_Mode << 30) | ((u32)CAN_InitStruct->CAN_SJW << 24) |
+ ((u32)CAN_InitStruct->CAN_BS1 << 16) | ((u32)CAN_InitStruct->CAN_BS2 << 20) |
+ ((u32)CAN_InitStruct->CAN_Prescaler - 1);
+
+ InitStatus = CANINITOK;
+
+ /* Request leave initialisation */
+ CAN->MCR &= ~CAN_MCR_INRQ;
+
+ /* Wait the acknowledge */
+ for(WaitAck = 0x400; WaitAck > 0x0; WaitAck--)
+ {
+ }
+
+ /* ...and check acknowledged */
+ if ((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK)
+ {
+ InitStatus = CANINITFAILED;
+ }
+ }
+
+ /* At this step, return the status of initialization */
+ return InitStatus;
+}
+
+/*******************************************************************************
+* Function Name : CAN_FilterInit
+* Description : Initializes the CAN peripheral according to the specified
+* parameters in the CAN_FilterInitStruct.
+* Input : CAN_FilterInitStruct: pointer to a CAN_FilterInitTypeDef
+* structure that contains the configuration information.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct)
+{
+ u16 FilterNumber_BitPos = 0;
+
+ /* Check the parameters */
+ assert_param(IS_CAN_FILTER_NUMBER(CAN_FilterInitStruct->CAN_FilterNumber));
+ assert_param(IS_CAN_FILTER_MODE(CAN_FilterInitStruct->CAN_FilterMode));
+ assert_param(IS_CAN_FILTER_SCALE(CAN_FilterInitStruct->CAN_FilterScale));
+ assert_param(IS_CAN_FILTER_FIFO(CAN_FilterInitStruct->CAN_FilterFIFOAssignment));
+ assert_param(IS_FUNCTIONAL_STATE(CAN_FilterInitStruct->CAN_FilterActivation));
+
+ FilterNumber_BitPos =
+ (u16)((u16)0x0001 << ((u16)CAN_FilterInitStruct->CAN_FilterNumber));
+
+ /* Initialisation mode for the filter */
+ CAN->FMR |= CAN_FMR_FINIT;
+
+ /* Filter Deactivation */
+ CAN->FA1R &= ~(u32)FilterNumber_BitPos;
+
+ /* Filter Scale */
+ if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_16bit)
+ {
+ /* 16-bit scale for the filter */
+ CAN->FS1R &= ~(u32)FilterNumber_BitPos;
+
+ /* First 16-bit identifier and First 16-bit mask */
+ /* Or First 16-bit identifier and Second 16-bit identifier */
+ CAN->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 =
+ ((u32)((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterMaskIdLow) << 16) |
+ ((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterIdLow);
+
+ /* Second 16-bit identifier and Second 16-bit mask */
+ /* Or Third 16-bit identifier and Fourth 16-bit identifier */
+ CAN->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 =
+ ((u32)((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) |
+ ((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterIdHigh);
+ }
+ if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_32bit)
+ {
+ /* 32-bit scale for the filter */
+ CAN->FS1R |= FilterNumber_BitPos;
+
+ /* 32-bit identifier or First 32-bit identifier */
+ CAN->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 =
+ ((u32)((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterIdHigh) << 16) |
+ ((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterIdLow);
+
+ /* 32-bit mask or Second 32-bit identifier */
+ CAN->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 =
+ ((u32)((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) |
+ ((u32)0x0000FFFF & CAN_FilterInitStruct->CAN_FilterMaskIdLow);
+
+ }
+
+ /* Filter Mode */
+ if (CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdMask)
+ {
+ /*Id/Mask mode for the filter*/
+ CAN->FM1R &= ~(u32)FilterNumber_BitPos;
+ }
+ else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */
+ {
+ /*Identifier list mode for the filter*/
+ CAN->FM1R |= (u32)FilterNumber_BitPos;
+ }
+
+ /* Filter FIFO assignment */
+ if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_FilterFIFO0)
+ {
+ /* FIFO 0 assignation for the filter */
+ CAN->FFA1R &= ~(u32)FilterNumber_BitPos;
+ }
+ if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_FilterFIFO1)
+ {
+ /* FIFO 1 assignation for the filter */
+ CAN->FFA1R |= (u32)FilterNumber_BitPos;
+ }
+
+ /* Filter activation */
+ if (CAN_FilterInitStruct->CAN_FilterActivation == ENABLE)
+ {
+ CAN->FA1R |= FilterNumber_BitPos;
+ }
+
+ /* Leave the initialisation mode for the filter */
+ CAN->FMR &= ~CAN_FMR_FINIT;
+}
+
+/*******************************************************************************
+* Function Name : CAN_StructInit
+* Description : Fills each CAN_InitStruct member with its default value.
+* Input : CAN_InitStruct: pointer to a CAN_InitTypeDef structure which
+* will be initialized.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct)
+{
+ /* Reset CAN init structure parameters values */
+
+ /* Initialize the time triggered communication mode */
+ CAN_InitStruct->CAN_TTCM = DISABLE;
+
+ /* Initialize the automatic bus-off management */
+ CAN_InitStruct->CAN_ABOM = DISABLE;
+
+ /* Initialize the automatic wake-up mode */
+ CAN_InitStruct->CAN_AWUM = DISABLE;
+
+ /* Initialize the no automatic retransmission */
+ CAN_InitStruct->CAN_NART = DISABLE;
+
+ /* Initialize the receive FIFO locked mode */
+ CAN_InitStruct->CAN_RFLM = DISABLE;
+
+ /* Initialize the transmit FIFO priority */
+ CAN_InitStruct->CAN_TXFP = DISABLE;
+
+ /* Initialize the CAN_Mode member */
+ CAN_InitStruct->CAN_Mode = CAN_Mode_Normal;
+
+ /* Initialize the CAN_SJW member */
+ CAN_InitStruct->CAN_SJW = CAN_SJW_1tq;
+
+ /* Initialize the CAN_BS1 member */
+ CAN_InitStruct->CAN_BS1 = CAN_BS1_4tq;
+
+ /* Initialize the CAN_BS2 member */
+ CAN_InitStruct->CAN_BS2 = CAN_BS2_3tq;
+
+ /* Initialize the CAN_Prescaler member */
+ CAN_InitStruct->CAN_Prescaler = 1;
+}
+
+/*******************************************************************************
+* Function Name : CAN_ITConfig
+* Description : Enables or disables the specified CAN interrupts.
+* Input : - CAN_IT: specifies the CAN interrupt sources to be enabled or
+* disabled.
+* This parameter can be: CAN_IT_TME, CAN_IT_FMP0, CAN_IT_FF0,
+* CAN_IT_FOV0, CAN_IT_FMP1, CAN_IT_FF1,
+* CAN_IT_FOV1, CAN_IT_EWG, CAN_IT_EPV,
+* CAN_IT_LEC, CAN_IT_ERR, CAN_IT_WKU or
+* CAN_IT_SLK.
+* - NewState: new state of the CAN interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_ITConfig(u32 CAN_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_CAN_ITConfig(CAN_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected CAN interrupt */
+ CAN->IER |= CAN_IT;
+ }
+ else
+ {
+ /* Disable the selected CAN interrupt */
+ CAN->IER &= ~CAN_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : CAN_Transmit
+* Description : Initiates the transmission of a message.
+* Input : TxMessage: pointer to a structure which contains CAN Id, CAN
+* DLC and CAN datas.
+* Output : None.
+* Return : The number of the mailbox that is used for transmission
+* or CAN_NO_MB if there is no empty mailbox.
+*******************************************************************************/
+u8 CAN_Transmit(CanTxMsg* TxMessage)
+{
+ u8 TransmitMailbox = 0;
+
+ /* Check the parameters */
+ assert_param(IS_CAN_STDID(TxMessage->StdId));
+ assert_param(IS_CAN_EXTID(TxMessage->StdId));
+ assert_param(IS_CAN_IDTYPE(TxMessage->IDE));
+ assert_param(IS_CAN_RTR(TxMessage->RTR));
+ assert_param(IS_CAN_DLC(TxMessage->DLC));
+
+ /* Select one empty transmit mailbox */
+ if ((CAN->TSR&CAN_TSR_TME0) == CAN_TSR_TME0)
+ {
+ TransmitMailbox = 0;
+ }
+ else if ((CAN->TSR&CAN_TSR_TME1) == CAN_TSR_TME1)
+ {
+ TransmitMailbox = 1;
+ }
+ else if ((CAN->TSR&CAN_TSR_TME2) == CAN_TSR_TME2)
+ {
+ TransmitMailbox = 2;
+ }
+ else
+ {
+ TransmitMailbox = CAN_NO_MB;
+ }
+
+ if (TransmitMailbox != CAN_NO_MB)
+ {
+ /* Set up the Id */
+ CAN->sTxMailBox[TransmitMailbox].TIR &= CAN_TMIDxR_TXRQ;
+ if (TxMessage->IDE == CAN_ID_STD)
+ {
+ TxMessage->StdId &= (u32)0x000007FF;
+ TxMessage->StdId = TxMessage->StdId << 21;
+
+ CAN->sTxMailBox[TransmitMailbox].TIR |= (TxMessage->StdId | TxMessage->IDE |
+ TxMessage->RTR);
+ }
+ else
+ {
+ TxMessage->ExtId &= (u32)0x1FFFFFFF;
+ TxMessage->ExtId <<= 3;
+
+ CAN->sTxMailBox[TransmitMailbox].TIR |= (TxMessage->ExtId | TxMessage->IDE |
+ TxMessage->RTR);
+ }
+
+ /* Set up the DLC */
+ TxMessage->DLC &= (u8)0x0000000F;
+ CAN->sTxMailBox[TransmitMailbox].TDTR &= (u32)0xFFFFFFF0;
+ CAN->sTxMailBox[TransmitMailbox].TDTR |= TxMessage->DLC;
+
+ /* Set up the data field */
+ CAN->sTxMailBox[TransmitMailbox].TDLR = (((u32)TxMessage->Data[3] << 24) |
+ ((u32)TxMessage->Data[2] << 16) |
+ ((u32)TxMessage->Data[1] << 8) |
+ ((u32)TxMessage->Data[0]));
+ CAN->sTxMailBox[TransmitMailbox].TDHR = (((u32)TxMessage->Data[7] << 24) |
+ ((u32)TxMessage->Data[6] << 16) |
+ ((u32)TxMessage->Data[5] << 8) |
+ ((u32)TxMessage->Data[4]));
+
+ /* Request transmission */
+ CAN->sTxMailBox[TransmitMailbox].TIR |= CAN_TMIDxR_TXRQ;
+ }
+
+ return TransmitMailbox;
+}
+
+/*******************************************************************************
+* Function Name : CAN_TransmitStatus
+* Description : Checks the transmission of a message.
+* Input : TransmitMailbox: the number of the mailbox that is used for
+* transmission.
+* Output : None.
+* Return : CANTXOK if the CAN driver transmits the message, CANTXFAILED
+* in an other case.
+*******************************************************************************/
+u8 CAN_TransmitStatus(u8 TransmitMailbox)
+{
+ /* RQCP, TXOK and TME bits */
+ u8 State = 0;
+
+ /* Check the parameters */
+ assert_param(IS_CAN_TRANSMITMAILBOX(TransmitMailbox));
+
+ switch (TransmitMailbox)
+ {
+ case (0): State |= (u8)((CAN->TSR & CAN_TSR_RQCP0) << 2);
+ State |= (u8)((CAN->TSR & CAN_TSR_TXOK0) >> 0);
+ State |= (u8)((CAN->TSR & CAN_TSR_TME0) >> 26);
+ break;
+ case (1): State |= (u8)((CAN->TSR & CAN_TSR_RQCP1) >> 6);
+ State |= (u8)((CAN->TSR & CAN_TSR_TXOK1) >> 8);
+ State |= (u8)((CAN->TSR & CAN_TSR_TME1) >> 27);
+ break;
+ case (2): State |= (u8)((CAN->TSR & CAN_TSR_RQCP2) >> 14);
+ State |= (u8)((CAN->TSR & CAN_TSR_TXOK2) >> 16);
+ State |= (u8)((CAN->TSR & CAN_TSR_TME2) >> 28);
+ break;
+ default:
+ State = CANTXFAILED;
+ break;
+ }
+
+ switch (State)
+ {
+ /* transmit pending */
+ case (0x0): State = CANTXPENDING;
+ break;
+ /* transmit failed */
+ case (0x5): State = CANTXFAILED;
+ break;
+ /* transmit succedeed */
+ case (0x7): State = CANTXOK;
+ break;
+ default:
+ State = CANTXFAILED;
+ break;
+ }
+
+ return State;
+}
+
+/*******************************************************************************
+* Function Name : CAN_CancelTransmit
+* Description : Cancels a transmit request.
+* Input : Mailbox number.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_CancelTransmit(u8 Mailbox)
+{
+ /* Check the parameters */
+ assert_param(IS_CAN_TRANSMITMAILBOX(Mailbox));
+
+ /* abort transmission */
+ switch (Mailbox)
+ {
+ case (0): CAN->TSR |= CAN_TSR_ABRQ0;
+ break;
+ case (1): CAN->TSR |= CAN_TSR_ABRQ1;
+ break;
+ case (2): CAN->TSR |= CAN_TSR_ABRQ2;
+ break;
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : CAN_FIFORelease
+* Description : Releases a FIFO.
+* Input : FIFONumber: FIFO to release, CAN_FIFO0 or CAN_FIFO1.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_FIFORelease(u8 FIFONumber)
+{
+ /* Check the parameters */
+ assert_param(IS_CAN_FIFO(FIFONumber));
+
+ /* Release FIFO0 */
+ if (FIFONumber == CAN_FIFO0)
+ {
+ CAN->RF0R = CAN_RF0R_RFOM0;
+ }
+ /* Release FIFO1 */
+ else /* FIFONumber == CAN_FIFO1 */
+ {
+ CAN->RF1R = CAN_RF1R_RFOM1;
+ }
+}
+
+/*******************************************************************************
+* Function Name : CAN_MessagePending
+* Description : Returns the number of pending messages.
+* Input : FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1.
+* Output : None.
+* Return : NbMessage which is the number of pending message.
+*******************************************************************************/
+u8 CAN_MessagePending(u8 FIFONumber)
+{
+ u8 MessagePending=0;
+
+ /* Check the parameters */
+ assert_param(IS_CAN_FIFO(FIFONumber));
+
+ if (FIFONumber == CAN_FIFO0)
+ {
+ MessagePending = (u8)(CAN->RF0R&(u32)0x03);
+ }
+ else if (FIFONumber == CAN_FIFO1)
+ {
+ MessagePending = (u8)(CAN->RF1R&(u32)0x03);
+ }
+ else
+ {
+ MessagePending = 0;
+ }
+ return MessagePending;
+}
+
+/*******************************************************************************
+* Function Name : CAN_Receive
+* Description : Receives a message.
+* Input : FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1.
+* Output : RxMessage: pointer to a structure which contains CAN Id,
+* CAN DLC, CAN datas and FMI number.
+* Return : None.
+*******************************************************************************/
+void CAN_Receive(u8 FIFONumber, CanRxMsg* RxMessage)
+{
+ /* Check the parameters */
+ assert_param(IS_CAN_FIFO(FIFONumber));
+
+ /* Get the Id */
+ RxMessage->IDE = (u8)0x04 & CAN->sFIFOMailBox[FIFONumber].RIR;
+ if (RxMessage->IDE == CAN_ID_STD)
+ {
+ RxMessage->StdId = (u32)0x000007FF & (CAN->sFIFOMailBox[FIFONumber].RIR >> 21);
+ }
+ else
+ {
+ RxMessage->ExtId = (u32)0x1FFFFFFF & (CAN->sFIFOMailBox[FIFONumber].RIR >> 3);
+ }
+
+ RxMessage->RTR = (u8)0x02 & CAN->sFIFOMailBox[FIFONumber].RIR;
+
+ /* Get the DLC */
+ RxMessage->DLC = (u8)0x0F & CAN->sFIFOMailBox[FIFONumber].RDTR;
+
+ /* Get the FMI */
+ RxMessage->FMI = (u8)0xFF & (CAN->sFIFOMailBox[FIFONumber].RDTR >> 8);
+
+ /* Get the data field */
+ RxMessage->Data[0] = (u8)0xFF & CAN->sFIFOMailBox[FIFONumber].RDLR;
+ RxMessage->Data[1] = (u8)0xFF & (CAN->sFIFOMailBox[FIFONumber].RDLR >> 8);
+ RxMessage->Data[2] = (u8)0xFF & (CAN->sFIFOMailBox[FIFONumber].RDLR >> 16);
+ RxMessage->Data[3] = (u8)0xFF & (CAN->sFIFOMailBox[FIFONumber].RDLR >> 24);
+
+ RxMessage->Data[4] = (u8)0xFF & CAN->sFIFOMailBox[FIFONumber].RDHR;
+ RxMessage->Data[5] = (u8)0xFF & (CAN->sFIFOMailBox[FIFONumber].RDHR >> 8);
+ RxMessage->Data[6] = (u8)0xFF & (CAN->sFIFOMailBox[FIFONumber].RDHR >> 16);
+ RxMessage->Data[7] = (u8)0xFF & (CAN->sFIFOMailBox[FIFONumber].RDHR >> 24);
+
+ /* Release the FIFO */
+ CAN_FIFORelease(FIFONumber);
+}
+
+/*******************************************************************************
+* Function Name : CAN_Sleep
+* Description : Enters the low power mode.
+* Input : None.
+* Output : None.
+* Return : CANSLEEPOK if sleep entered, CANSLEEPFAILED in an other case.
+*******************************************************************************/
+u8 CAN_Sleep(void)
+{
+ u8 SleepStatus = 0;
+
+ /* Sleep mode entering request */
+ CAN->MCR |= CAN_MCR_SLEEP;
+ SleepStatus = CANSLEEPOK;
+
+ /* Sleep mode status */
+ if ((CAN->MCR&CAN_MCR_SLEEP) == 0)
+ {
+ /* Sleep mode not entered */
+ SleepStatus = CANSLEEPFAILED;
+ }
+
+ /* At this step, sleep mode status */
+ return SleepStatus;
+}
+
+/*******************************************************************************
+* Function Name : CAN_WakeUp
+* Description : Wakes the CAN up.
+* Input : None.
+* Output : None.
+* Return : CANWAKEUPOK if sleep mode left, CANWAKEUPFAILED in an other
+* case.
+*******************************************************************************/
+u8 CAN_WakeUp(void)
+{
+ u8 WakeUpStatus = 0;
+
+ /* Wake up request */
+ CAN->MCR &= ~CAN_MCR_SLEEP;
+ WakeUpStatus = CANWAKEUPFAILED;
+
+ /* Sleep mode status */
+ if ((CAN->MCR&CAN_MCR_SLEEP) == 0)
+ {
+ /* Sleep mode exited */
+ WakeUpStatus = CANWAKEUPOK;
+ }
+
+ /* At this step, sleep mode status */
+ return WakeUpStatus;
+}
+
+/*******************************************************************************
+* Function Name : CAN_GetFlagStatus
+* Description : Checks whether the specified CAN flag is set or not.
+* Input : CAN_FLAG: specifies the flag to check.
+* This parameter can be: CAN_FLAG_EWG, CAN_FLAG_EPV or
+* CAN_FLAG_BOF.
+* Output : None.
+* Return : The new state of CAN_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus CAN_GetFlagStatus(u32 CAN_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_CAN_FLAG(CAN_FLAG));
+
+ /* Check the status of the specified CAN flag */
+ if ((CAN->ESR & CAN_FLAG) != (u32)RESET)
+ {
+ /* CAN_FLAG is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* CAN_FLAG is reset */
+ bitstatus = RESET;
+ }
+ /* Return the CAN_FLAG status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : CAN_ClearFlag
+* Description : Clears the CAN's pending flags.
+* Input : CAN_FLAG: specifies the flag to clear.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_ClearFlag(u32 CAN_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_CAN_FLAG(CAN_FLAG));
+
+ /* Clear the selected CAN flags */
+ CAN->ESR &= ~CAN_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : CAN_GetITStatus
+* Description : Checks whether the specified CAN interrupt has occurred or
+* not.
+* Input : CAN_IT: specifies the CAN interrupt source to check.
+* This parameter can be: CAN_IT_RQCP0, CAN_IT_RQCP1, CAN_IT_RQCP2,
+* CAN_IT_FF0, CAN_IT_FOV0, CAN_IT_FF1,
+* CAN_IT_FOV1, CAN_IT_EWG, CAN_IT_EPV,
+* CAN_IT_BOF, CAN_IT_WKU or CAN_IT_SLK.
+* Output : None.
+* Return : The new state of CAN_IT (SET or RESET).
+*******************************************************************************/
+ITStatus CAN_GetITStatus(u32 CAN_IT)
+{
+ ITStatus pendingbitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_CAN_ITStatus(CAN_IT));
+
+ switch (CAN_IT)
+ {
+ case CAN_IT_RQCP0:
+ pendingbitstatus = CheckITStatus(CAN->TSR, CAN_TSR_RQCP0);
+ break;
+ case CAN_IT_RQCP1:
+ pendingbitstatus = CheckITStatus(CAN->TSR, CAN_TSR_RQCP1);
+ break;
+ case CAN_IT_RQCP2:
+ pendingbitstatus = CheckITStatus(CAN->TSR, CAN_TSR_RQCP2);
+ break;
+ case CAN_IT_FF0:
+ pendingbitstatus = CheckITStatus(CAN->RF0R, CAN_RF0R_FULL0);
+ break;
+ case CAN_IT_FOV0:
+ pendingbitstatus = CheckITStatus(CAN->RF0R, CAN_RF0R_FOVR0);
+ break;
+ case CAN_IT_FF1:
+ pendingbitstatus = CheckITStatus(CAN->RF1R, CAN_RF1R_FULL1);
+ break;
+ case CAN_IT_FOV1:
+ pendingbitstatus = CheckITStatus(CAN->RF1R, CAN_RF1R_FOVR1);
+ break;
+ case CAN_IT_EWG:
+ pendingbitstatus = CheckITStatus(CAN->ESR, CAN_ESR_EWGF);
+ break;
+ case CAN_IT_EPV:
+ pendingbitstatus = CheckITStatus(CAN->ESR, CAN_ESR_EPVF);
+ break;
+ case CAN_IT_BOF:
+ pendingbitstatus = CheckITStatus(CAN->ESR, CAN_ESR_BOFF);
+ break;
+ case CAN_IT_SLK:
+ pendingbitstatus = CheckITStatus(CAN->MSR, CAN_MSR_SLAKI);
+ break;
+ case CAN_IT_WKU:
+ pendingbitstatus = CheckITStatus(CAN->MSR, CAN_MSR_WKUI);
+ break;
+
+ default :
+ pendingbitstatus = RESET;
+ break;
+ }
+
+ /* Return the CAN_IT status */
+ return pendingbitstatus;
+}
+
+/*******************************************************************************
+* Function Name : CAN_ClearITPendingBit
+* Description : Clears the CAN’s interrupt pending bits.
+* Input : CAN_IT: specifies the interrupt pending bit to clear.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+void CAN_ClearITPendingBit(u32 CAN_IT)
+{
+ /* Check the parameters */
+ assert_param(IS_CAN_ITStatus(CAN_IT));
+
+ switch (CAN_IT)
+ {
+ case CAN_IT_RQCP0:
+ CAN->TSR = CAN_TSR_RQCP0; /* rc_w1*/
+ break;
+ case CAN_IT_RQCP1:
+ CAN->TSR = CAN_TSR_RQCP1; /* rc_w1*/
+ break;
+ case CAN_IT_RQCP2:
+ CAN->TSR = CAN_TSR_RQCP2; /* rc_w1*/
+ break;
+ case CAN_IT_FF0:
+ CAN->RF0R = CAN_RF0R_FULL0; /* rc_w1*/
+ break;
+ case CAN_IT_FOV0:
+ CAN->RF0R = CAN_RF0R_FOVR0; /* rc_w1*/
+ break;
+ case CAN_IT_FF1:
+ CAN->RF1R = CAN_RF1R_FULL1; /* rc_w1*/
+ break;
+ case CAN_IT_FOV1:
+ CAN->RF1R = CAN_RF1R_FOVR1; /* rc_w1*/
+ break;
+ case CAN_IT_EWG:
+ CAN->ESR &= ~ CAN_ESR_EWGF; /* rw */
+ break;
+ case CAN_IT_EPV:
+ CAN->ESR &= ~ CAN_ESR_EPVF; /* rw */
+ break;
+ case CAN_IT_BOF:
+ CAN->ESR &= ~ CAN_ESR_BOFF; /* rw */
+ break;
+ case CAN_IT_WKU:
+ CAN->MSR = CAN_MSR_WKUI; /* rc_w1*/
+ break;
+ case CAN_IT_SLK:
+ CAN->MSR = CAN_MSR_SLAKI; /* rc_w1*/
+ break;
+ default :
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : CheckITStatus
+* Description : Checks whether the CAN interrupt has occurred or not.
+* Input : CAN_Reg: specifies the CAN interrupt register to check.
+* It_Bit: specifies the interrupt source bit to check.
+* Output : None.
+* Return : The new state of the CAN Interrupt (SET or RESET).
+*******************************************************************************/
+static ITStatus CheckITStatus(u32 CAN_Reg, u32 It_Bit)
+{
+ ITStatus pendingbitstatus = RESET;
+
+ if ((CAN_Reg & It_Bit) != (u32)RESET)
+ {
+ /* CAN_IT is set */
+ pendingbitstatus = SET;
+ }
+ else
+ {
+ /* CAN_IT is reset */
+ pendingbitstatus = RESET;
+ }
+
+ return pendingbitstatus;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_crc.c b/src/stm32lib/src/stm32f10x_crc.c new file mode 100644 index 0000000..ac8c7c4 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_crc.c @@ -0,0 +1,114 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_crc.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the CRC firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_crc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* CR register bit mask */
+#define CR_RESET_Set ((u32)0x00000001)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : CRC_ResetDR
+* Description : Resets the CRC Data register (DR).
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void CRC_ResetDR(void)
+{
+ /* Reset CRC generator */
+ CRC->CR = CR_RESET_Set;
+}
+
+/*******************************************************************************
+* Function Name : CRC_CalcCRC
+* Description : Computes the 32-bit CRC of a given data word(32-bit).
+* Input : - Data: data word(32-bit) to compute its CRC
+* Output : None
+* Return : 32-bit CRC
+*******************************************************************************/
+u32 CRC_CalcCRC(u32 Data)
+{
+ CRC->DR = Data;
+
+ return (CRC->DR);
+}
+
+/*******************************************************************************
+* Function Name : CRC_CalcBlockCRC
+* Description : Computes the 32-bit CRC of a given buffer of data word(32-bit).
+* Input : - pBuffer: pointer to the buffer containing the data to be
+* computed
+* - BufferLength: length of the buffer to be computed
+* Output : None
+* Return : 32-bit CRC
+*******************************************************************************/
+u32 CRC_CalcBlockCRC(u32 pBuffer[], u32 BufferLength)
+{
+ u32 index = 0;
+
+ for(index = 0; index < BufferLength; index++)
+ {
+ CRC->DR = pBuffer[index];
+ }
+
+ return (CRC->DR);
+}
+
+/*******************************************************************************
+* Function Name : CRC_GetCRC
+* Description : Returns the current CRC value.
+* Input : None
+* Output : None
+* Return : 32-bit CRC
+*******************************************************************************/
+u32 CRC_GetCRC(void)
+{
+ return (CRC->DR);
+}
+
+/*******************************************************************************
+* Function Name : CRC_SetIDRegister
+* Description : Stores a 8-bit data in the Independent Data(ID) register.
+* Input : - IDValue: 8-bit value to be stored in the ID register
+* Output : None
+* Return : None
+*******************************************************************************/
+void CRC_SetIDRegister(u8 IDValue)
+{
+ CRC->IDR = IDValue;
+}
+
+/*******************************************************************************
+* Function Name : CRC_GetIDRegister
+* Description : Returns the 8-bit data stored in the Independent Data(ID) register
+* Input : None
+* Output : None
+* Return : 8-bit value of the ID register
+*******************************************************************************/
+u8 CRC_GetIDRegister(void)
+{
+ return (CRC->IDR);
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_dac.c b/src/stm32lib/src/stm32f10x_dac.c new file mode 100644 index 0000000..80eec1a --- /dev/null +++ b/src/stm32lib/src/stm32f10x_dac.c @@ -0,0 +1,389 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_dac.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the DAC firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_dac.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* DAC EN mask */
+#define CR_EN_Set ((u32)0x00000001)
+
+/* DAC DMAEN mask */
+#define CR_DMAEN_Set ((u32)0x00001000)
+
+/* CR register Mask */
+#define CR_CLEAR_Mask ((u32)0x00000FFE)
+
+/* DAC SWTRIG mask */
+#define SWTRIGR_SWTRIG_Set ((u32)0x00000001)
+
+/* DAC Dual Channels SWTRIG masks */
+#define DUAL_SWTRIG_Set ((u32)0x00000003)
+#define DUAL_SWTRIG_Reset ((u32)0xFFFFFFFC)
+
+/* DHR registers offsets */
+#define DHR12R1_Offset ((u32)0x00000008)
+#define DHR12R2_Offset ((u32)0x00000014)
+#define DHR12RD_Offset ((u32)0x00000020)
+
+/* DOR register offset */
+#define DOR_Offset ((u32)0x0000002C)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : DAC_DeInit
+* Description : Deinitializes the DAC peripheral registers to their default
+* reset values.
+* Input : None.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_DeInit(void)
+{
+ /* Enable DAC reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, ENABLE);
+ /* Release DAC from reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, DISABLE);
+}
+
+/*******************************************************************************
+* Function Name : DAC_Init
+* Description : Initializes the DAC peripheral according to the specified
+* parameters in the DAC_InitStruct.
+* Input : - DAC_Channel: the selected DAC channel.
+* This parameter can be one of the following values:
+* - DAC_Channel_1: DAC Channel1 selected
+* - DAC_Channel_2: DAC Channel2 selected
+* - DAC_InitStruct: pointer to a DAC_InitTypeDef structure that
+* contains the configuration information for the specified
+* DAC channel.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_Init(u32 DAC_Channel, DAC_InitTypeDef* DAC_InitStruct)
+{
+ u32 tmpreg1 = 0, tmpreg2 = 0;
+
+ /* Check the DAC parameters */
+ assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger));
+ assert_param(IS_DAC_GENERATE_WAVE(DAC_InitStruct->DAC_WaveGeneration));
+ assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude));
+ assert_param(IS_DAC_OUTPUT_BUFFER_STATE(DAC_InitStruct->DAC_OutputBuffer));
+
+/*---------------------------- DAC CR Configuration --------------------------*/
+ /* Get the DAC CR value */
+ tmpreg1 = DAC->CR;
+ /* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */
+ tmpreg1 &= ~(CR_CLEAR_Mask << DAC_Channel);
+ /* Configure for the selected DAC channel: buffer output, trigger, wave genration,
+ mask/amplitude for wave genration */
+ /* Set TSELx and TENx bits according to DAC_Trigger value */
+ /* Set WAVEx bits according to DAC_WaveGeneration value */
+ /* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */
+ /* Set BOFFx bit according to DAC_OutputBuffer value */
+ tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration |
+ DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | DAC_InitStruct->DAC_OutputBuffer);
+ /* Calculate CR register value depending on DAC_Channel */
+ tmpreg1 |= tmpreg2 << DAC_Channel;
+ /* Write to DAC CR */
+ DAC->CR = tmpreg1;
+}
+
+/*******************************************************************************
+* Function Name : DAC_StructInit
+* Description : Fills each DAC_InitStruct member with its default value.
+* Input : - DAC_InitStruct : pointer to a DAC_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct)
+{
+/*--------------- Reset DAC init structure parameters values -----------------*/
+ /* Initialize the DAC_Trigger member */
+ DAC_InitStruct->DAC_Trigger = DAC_Trigger_None;
+
+ /* Initialize the DAC_WaveGeneration member */
+ DAC_InitStruct->DAC_WaveGeneration = DAC_WaveGeneration_None;
+
+ /* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */
+ DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0;
+
+ /* Initialize the DAC_OutputBuffer member */
+ DAC_InitStruct->DAC_OutputBuffer = DAC_OutputBuffer_Enable;
+}
+
+/*******************************************************************************
+* Function Name : DAC_Cmd
+* Description : Enables or disables the specified DAC channel.
+* Input - DAC_Channel: the selected DAC channel.
+* This parameter can be one of the following values:
+* - DAC_Channel_1: DAC Channel1 selected
+* - DAC_Channel_2: DAC Channel2 selected
+* - NewState: new state of the DAC channel.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_Cmd(u32 DAC_Channel, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_DAC_CHANNEL(DAC_Channel));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected DAC channel */
+ DAC->CR |= CR_EN_Set << DAC_Channel;
+ }
+ else
+ {
+ /* Disable the selected DAC channel */
+ DAC->CR &= ~(CR_EN_Set << DAC_Channel);
+ }
+}
+
+/*******************************************************************************
+* Function Name : DAC_DMACmd
+* Description : Enables or disables the specified DAC channel DMA request.
+* Input - DAC_Channel: the selected DAC channel.
+* This parameter can be one of the following values:
+* - DAC_Channel_1: DAC Channel1 selected
+* - DAC_Channel_2: DAC Channel2 selected
+* - NewState: new state of the selected DAC channel DMA request.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_DMACmd(u32 DAC_Channel, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_DAC_CHANNEL(DAC_Channel));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected DAC channel DMA request */
+ DAC->CR |= CR_DMAEN_Set << DAC_Channel;
+ }
+ else
+ {
+ /* Disable the selected DAC channel DMA request */
+ DAC->CR &= ~(CR_DMAEN_Set << DAC_Channel);
+ }
+}
+
+/*******************************************************************************
+* Function Name : DAC_SoftwareTriggerCmd
+* Description : Enables or disables the selected DAC channel software trigger.
+* Input - DAC_Channel: the selected DAC channel.
+* This parameter can be one of the following values:
+* - DAC_Channel_1: DAC Channel1 selected
+* - DAC_Channel_2: DAC Channel2 selected
+* - NewState: new state of the selected DAC channel software trigger.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_SoftwareTriggerCmd(u32 DAC_Channel, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_DAC_CHANNEL(DAC_Channel));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable software trigger for the selected DAC channel */
+ DAC->SWTRIGR |= SWTRIGR_SWTRIG_Set << (DAC_Channel >> 4);
+ }
+ else
+ {
+ /* Disable software trigger for the selected DAC channel */
+ DAC->SWTRIGR &= ~(SWTRIGR_SWTRIG_Set << (DAC_Channel >> 4));
+ }
+}
+
+/*******************************************************************************
+* Function Name : DAC_DualSoftwareTriggerCmd
+* Description : Enables or disables simultaneously the two DAC channels software
+* triggers.
+* Input - NewState: new state of the DAC channels software triggers.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_DualSoftwareTriggerCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable software trigger for both DAC channels */
+ DAC->SWTRIGR |= DUAL_SWTRIG_Set ;
+ }
+ else
+ {
+ /* Disable software trigger for both DAC channels */
+ DAC->SWTRIGR &= DUAL_SWTRIG_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : DAC_WaveGenerationCmd
+* Description : Enables or disables the selected DAC channel wave generation.
+* Input - DAC_Channel: the selected DAC channel.
+* This parameter can be one of the following values:
+* - DAC_Channel_1: DAC Channel1 selected
+* - DAC_Channel_2: DAC Channel2 selected
+* - DAC_Wave: Specifies the wave type to enable or disable.
+* This parameter can be one of the following values:
+* - DAC_Wave_Noise: noise wave generation
+* - DAC_Wave_Triangle: triangle wave generation
+* - NewState: new state of the selected DAC channel wave generation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_WaveGenerationCmd(u32 DAC_Channel, u32 DAC_Wave, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_DAC_CHANNEL(DAC_Channel));
+ assert_param(IS_DAC_WAVE(DAC_Wave));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected wave generation for the selected DAC channel */
+ DAC->CR |= DAC_Wave << DAC_Channel;
+ }
+ else
+ {
+ /* Disable the selected wave generation for the selected DAC channel */
+ DAC->CR &= ~(DAC_Wave << DAC_Channel);
+ }
+}
+
+/*******************************************************************************
+* Function Name : DAC_SetChannel1Data
+* Description : Set the specified data holding register value for DAC channel1.
+* Input : - DAC_Align: Specifies the data alignement for DAC channel1.
+* This parameter can be one of the following values:
+* - DAC_Align_8b_R: 8bit right data alignement selected
+* - DAC_Align_12b_L: 12bit left data alignement selected
+* - DAC_Align_12b_R: 12bit right data alignement selected
+* - Data : Data to be loaded in the selected data holding
+* register.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_SetChannel1Data(u32 DAC_Align, u16 Data)
+{
+ /* Check the parameters */
+ assert_param(IS_DAC_ALIGN(DAC_Align));
+ assert_param(IS_DAC_DATA(Data));
+
+ /* Set the DAC channel1 selected data holding register */
+ *((vu32 *)(DAC_BASE + DHR12R1_Offset + DAC_Align)) = (u32)Data;
+}
+
+/*******************************************************************************
+* Function Name : DAC_SetChannel2Data
+* Description : Set the specified data holding register value for DAC channel2.
+* Input : - DAC_Align: Specifies the data alignement for DAC channel2.
+* This parameter can be one of the following values:
+* - DAC_Align_8b_R: 8bit right data alignement selected
+* - DAC_Align_12b_L: 12bit left data alignement selected
+* - DAC_Align_12b_R: 12bit right data alignement selected
+* - Data : Data to be loaded in the selected data holding
+* register.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_SetChannel2Data(u32 DAC_Align, u16 Data)
+{
+ /* Check the parameters */
+ assert_param(IS_DAC_ALIGN(DAC_Align));
+ assert_param(IS_DAC_DATA(Data));
+
+ /* Set the DAC channel2 selected data holding register */
+ *((vu32 *)(DAC_BASE + DHR12R2_Offset + DAC_Align)) = (u32)Data;
+}
+
+/*******************************************************************************
+* Function Name : DAC_SetDualChannelData
+* Description : Set the specified data holding register value for dual channel
+* DAC.
+* Input : - DAC_Align: Specifies the data alignement for dual channel DAC.
+* This parameter can be one of the following values:
+* - DAC_Align_8b_R: 8bit right data alignement selected
+* - DAC_Align_12b_L: 12bit left data alignement selected
+* - DAC_Align_12b_R: 12bit right data alignement selected
+* - Data2: Data for DAC Channel2 to be loaded in the selected data
+* holding register.
+* - Data1: Data for DAC Channel1 to be loaded in the selected data
+* holding register.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DAC_SetDualChannelData(u32 DAC_Align, u16 Data2, u16 Data1)
+{
+ u32 data = 0;
+
+ /* Check the parameters */
+ assert_param(IS_DAC_ALIGN(DAC_Align));
+ assert_param(IS_DAC_DATA(Data1));
+ assert_param(IS_DAC_DATA(Data2));
+
+ /* Calculate and set dual DAC data holding register value */
+ if (DAC_Align == DAC_Align_8b_R)
+ {
+ data = ((u32)Data2 << 8) | Data1;
+ }
+ else
+ {
+ data = ((u32)Data2 << 16) | Data1;
+ }
+
+ /* Set the dual DAC selected data holding register */
+ *((vu32 *)(DAC_BASE + DHR12RD_Offset + DAC_Align)) = data;
+}
+
+/*******************************************************************************
+* Function Name : DAC_GetDataOutputValue
+* Description : Returns the last data output value of the selected DAC cahnnel.
+* Input - DAC_Channel: the selected DAC channel.
+* This parameter can be one of the following values:
+* - DAC_Channel_1: DAC Channel1 selected
+* - DAC_Channel_2: DAC Channel2 selected
+* Output : None
+* Return : The selected DAC channel data output value.
+*******************************************************************************/
+u16 DAC_GetDataOutputValue(u32 DAC_Channel)
+{
+ /* Check the parameters */
+ assert_param(IS_DAC_CHANNEL(DAC_Channel));
+
+ /* Returns the DAC channel data output register value */
+ return (u16) (*(vu32*)(DAC_BASE + DOR_Offset + ((u32)DAC_Channel >> 2)));
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_dbgmcu.c b/src/stm32lib/src/stm32f10x_dbgmcu.c new file mode 100644 index 0000000..04103b1 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_dbgmcu.c @@ -0,0 +1,97 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_dbgmcu.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the DBGMCU firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_dbgmcu.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define IDCODE_DEVID_Mask ((u32)0x00000FFF)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : DBGMCU_GetREVID
+* Description : Returns the device revision identifier.
+* Input : None
+* Output : None
+* Return : Device revision identifier
+*******************************************************************************/
+u32 DBGMCU_GetREVID(void)
+{
+ return(DBGMCU->IDCODE >> 16);
+}
+
+/*******************************************************************************
+* Function Name : DBGMCU_GetDEVID
+* Description : Returns the device identifier.
+* Input : None
+* Output : None
+* Return : Device identifier
+*******************************************************************************/
+u32 DBGMCU_GetDEVID(void)
+{
+ return(DBGMCU->IDCODE & IDCODE_DEVID_Mask);
+}
+
+/*******************************************************************************
+* Function Name : DBGMCU_Config
+* Description : Configures the specified peripheral and low power mode behavior
+* when the MCU under Debug mode.
+* Input : - DBGMCU_Periph: specifies the peripheral and low power mode.
+* This parameter can be any combination of the following values:
+* - DBGMCU_SLEEP: Keep debugger connection during SLEEP mode
+* - DBGMCU_STOP: Keep debugger connection during STOP mode
+* - DBGMCU_STANDBY: Keep debugger connection during STANDBY mode
+* - DBGMCU_IWDG_STOP: Debug IWDG stopped when Core is halted
+* - DBGMCU_WWDG_STOP: Debug WWDG stopped when Core is halted
+* - DBGMCU_TIM1_STOP: TIM1 counter stopped when Core is halted
+* - DBGMCU_TIM2_STOP: TIM2 counter stopped when Core is halted
+* - DBGMCU_TIM3_STOP: TIM3 counter stopped when Core is halted
+* - DBGMCU_TIM4_STOP: TIM4 counter stopped when Core is halted
+* - DBGMCU_CAN_STOP: Debug CAN stopped when Core is halted
+* - DBGMCU_I2C1_SMBUS_TIMEOUT: I2C1 SMBUS timeout mode stopped
+* when Core is halted
+* - DBGMCU_I2C2_SMBUS_TIMEOUT: I2C2 SMBUS timeout mode stopped
+* when Core is halted
+* - DBGMCU_TIM5_STOP: TIM5 counter stopped when Core is halted
+* - DBGMCU_TIM6_STOP: TIM6 counter stopped when Core is halted
+* - DBGMCU_TIM7_STOP: TIM7 counter stopped when Core is halted
+* - DBGMCU_TIM8_STOP: TIM8 counter stopped when Core is halted
+* - NewState: new state of the specified peripheral in Debug mode.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DBGMCU_Config(u32 DBGMCU_Periph, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_DBGMCU_PERIPH(DBGMCU_Periph));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ DBGMCU->CR |= DBGMCU_Periph;
+ }
+ else
+ {
+ DBGMCU->CR &= ~DBGMCU_Periph;
+ }
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_dma.c b/src/stm32lib/src/stm32f10x_dma.c new file mode 100644 index 0000000..eaefcb9 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_dma.c @@ -0,0 +1,678 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_dma.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the DMA firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_dma.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* DMA ENABLE mask */
+#define CCR_ENABLE_Set ((u32)0x00000001)
+#define CCR_ENABLE_Reset ((u32)0xFFFFFFFE)
+
+/* DMA1 Channelx interrupt pending bit masks */
+#define DMA1_Channel1_IT_Mask ((u32)0x0000000F)
+#define DMA1_Channel2_IT_Mask ((u32)0x000000F0)
+#define DMA1_Channel3_IT_Mask ((u32)0x00000F00)
+#define DMA1_Channel4_IT_Mask ((u32)0x0000F000)
+#define DMA1_Channel5_IT_Mask ((u32)0x000F0000)
+#define DMA1_Channel6_IT_Mask ((u32)0x00F00000)
+#define DMA1_Channel7_IT_Mask ((u32)0x0F000000)
+
+/* DMA2 Channelx interrupt pending bit masks */
+#define DMA2_Channel1_IT_Mask ((u32)0x0000000F)
+#define DMA2_Channel2_IT_Mask ((u32)0x000000F0)
+#define DMA2_Channel3_IT_Mask ((u32)0x00000F00)
+#define DMA2_Channel4_IT_Mask ((u32)0x0000F000)
+#define DMA2_Channel5_IT_Mask ((u32)0x000F0000)
+
+/* DMA2 FLAG mask */
+#define FLAG_Mask ((u32)0x10000000)
+
+/* DMA registers Masks */
+#define CCR_CLEAR_Mask ((u32)0xFFFF800F)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : DMA_DeInit
+* Description : Deinitializes the DMAy Channelx registers to their default reset
+* values.
+* Input : - DMAy_Channelx: where y can be 1 or 2 to select the DMA and
+* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the
+* DMA Channel.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx)
+{
+ /* Check the parameters */
+ assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+
+ /* Disable the selected DMAy Channelx */
+ DMAy_Channelx->CCR &= CCR_ENABLE_Reset;
+
+ /* Reset DMAy Channelx control register */
+ DMAy_Channelx->CCR = 0;
+
+ /* Reset DMAy Channelx remaining bytes register */
+ DMAy_Channelx->CNDTR = 0;
+
+ /* Reset DMAy Channelx peripheral address register */
+ DMAy_Channelx->CPAR = 0;
+
+ /* Reset DMAy Channelx memory address register */
+ DMAy_Channelx->CMAR = 0;
+
+ switch (*(u32*)&DMAy_Channelx)
+ {
+ case DMA1_Channel1_BASE:
+ /* Reset interrupt pending bits for DMA1 Channel1 */
+ DMA1->IFCR |= DMA1_Channel1_IT_Mask;
+ break;
+
+ case DMA1_Channel2_BASE:
+ /* Reset interrupt pending bits for DMA1 Channel2 */
+ DMA1->IFCR |= DMA1_Channel2_IT_Mask;
+ break;
+
+ case DMA1_Channel3_BASE:
+ /* Reset interrupt pending bits for DMA1 Channel3 */
+ DMA1->IFCR |= DMA1_Channel3_IT_Mask;
+ break;
+
+ case DMA1_Channel4_BASE:
+ /* Reset interrupt pending bits for DMA1 Channel4 */
+ DMA1->IFCR |= DMA1_Channel4_IT_Mask;
+ break;
+
+ case DMA1_Channel5_BASE:
+ /* Reset interrupt pending bits for DMA1 Channel5 */
+ DMA1->IFCR |= DMA1_Channel5_IT_Mask;
+ break;
+
+ case DMA1_Channel6_BASE:
+ /* Reset interrupt pending bits for DMA1 Channel6 */
+ DMA1->IFCR |= DMA1_Channel6_IT_Mask;
+ break;
+
+ case DMA1_Channel7_BASE:
+ /* Reset interrupt pending bits for DMA1 Channel7 */
+ DMA1->IFCR |= DMA1_Channel7_IT_Mask;
+ break;
+
+ case DMA2_Channel1_BASE:
+ /* Reset interrupt pending bits for DMA2 Channel1 */
+ DMA2->IFCR |= DMA2_Channel1_IT_Mask;
+ break;
+
+ case DMA2_Channel2_BASE:
+ /* Reset interrupt pending bits for DMA2 Channel2 */
+ DMA2->IFCR |= DMA2_Channel2_IT_Mask;
+ break;
+
+ case DMA2_Channel3_BASE:
+ /* Reset interrupt pending bits for DMA2 Channel3 */
+ DMA2->IFCR |= DMA2_Channel3_IT_Mask;
+ break;
+
+ case DMA2_Channel4_BASE:
+ /* Reset interrupt pending bits for DMA2 Channel4 */
+ DMA2->IFCR |= DMA2_Channel4_IT_Mask;
+ break;
+
+ case DMA2_Channel5_BASE:
+ /* Reset interrupt pending bits for DMA2 Channel5 */
+ DMA2->IFCR |= DMA2_Channel5_IT_Mask;
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : DMA_Init
+* Description : Initializes the DMAy Channelx according to the specified
+* parameters in the DMA_InitStruct.
+* Input : - DMAy_Channelx: where y can be 1 or 2 to select the DMA and
+* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the
+* DMA Channel.
+* - DMA_InitStruct: pointer to a DMA_InitTypeDef structure that
+* contains the configuration information for the specified
+* DMA Channel.
+* Output : None
+* Return : None
+******************************************************************************/
+void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+ assert_param(IS_DMA_DIR(DMA_InitStruct->DMA_DIR));
+ assert_param(IS_DMA_BUFFER_SIZE(DMA_InitStruct->DMA_BufferSize));
+ assert_param(IS_DMA_PERIPHERAL_INC_STATE(DMA_InitStruct->DMA_PeripheralInc));
+ assert_param(IS_DMA_MEMORY_INC_STATE(DMA_InitStruct->DMA_MemoryInc));
+ assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(DMA_InitStruct->DMA_PeripheralDataSize));
+ assert_param(IS_DMA_MEMORY_DATA_SIZE(DMA_InitStruct->DMA_MemoryDataSize));
+ assert_param(IS_DMA_MODE(DMA_InitStruct->DMA_Mode));
+ assert_param(IS_DMA_PRIORITY(DMA_InitStruct->DMA_Priority));
+ assert_param(IS_DMA_M2M_STATE(DMA_InitStruct->DMA_M2M));
+
+/*--------------------------- DMAy Channelx CCR Configuration -----------------*/
+ /* Get the DMAy_Channelx CCR value */
+ tmpreg = DMAy_Channelx->CCR;
+ /* Clear MEM2MEM, PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */
+ tmpreg &= CCR_CLEAR_Mask;
+ /* Configure DMAy Channelx: data transfer, data size, priority level and mode */
+ /* Set DIR bit according to DMA_DIR value */
+ /* Set CIRC bit according to DMA_Mode value */
+ /* Set PINC bit according to DMA_PeripheralInc value */
+ /* Set MINC bit according to DMA_MemoryInc value */
+ /* Set PSIZE bits according to DMA_PeripheralDataSize value */
+ /* Set MSIZE bits according to DMA_MemoryDataSize value */
+ /* Set PL bits according to DMA_Priority value */
+ /* Set the MEM2MEM bit according to DMA_M2M value */
+ tmpreg |= DMA_InitStruct->DMA_DIR | DMA_InitStruct->DMA_Mode |
+ DMA_InitStruct->DMA_PeripheralInc | DMA_InitStruct->DMA_MemoryInc |
+ DMA_InitStruct->DMA_PeripheralDataSize | DMA_InitStruct->DMA_MemoryDataSize |
+ DMA_InitStruct->DMA_Priority | DMA_InitStruct->DMA_M2M;
+ /* Write to DMAy Channelx CCR */
+ DMAy_Channelx->CCR = tmpreg;
+
+/*--------------------------- DMAy Channelx CNDTR Configuration ---------------*/
+ /* Write to DMAy Channelx CNDTR */
+ DMAy_Channelx->CNDTR = DMA_InitStruct->DMA_BufferSize;
+
+/*--------------------------- DMAy Channelx CPAR Configuration ----------------*/
+ /* Write to DMAy Channelx CPAR */
+ DMAy_Channelx->CPAR = DMA_InitStruct->DMA_PeripheralBaseAddr;
+
+/*--------------------------- DMAy Channelx CMAR Configuration ----------------*/
+ /* Write to DMAy Channelx CMAR */
+ DMAy_Channelx->CMAR = DMA_InitStruct->DMA_MemoryBaseAddr;
+}
+
+/*******************************************************************************
+* Function Name : DMA_StructInit
+* Description : Fills each DMA_InitStruct member with its default value.
+* Input : - DMA_InitStruct : pointer to a DMA_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct)
+{
+/*-------------- Reset DMA init structure parameters values ------------------*/
+ /* Initialize the DMA_PeripheralBaseAddr member */
+ DMA_InitStruct->DMA_PeripheralBaseAddr = 0;
+
+ /* Initialize the DMA_MemoryBaseAddr member */
+ DMA_InitStruct->DMA_MemoryBaseAddr = 0;
+
+ /* Initialize the DMA_DIR member */
+ DMA_InitStruct->DMA_DIR = DMA_DIR_PeripheralSRC;
+
+ /* Initialize the DMA_BufferSize member */
+ DMA_InitStruct->DMA_BufferSize = 0;
+
+ /* Initialize the DMA_PeripheralInc member */
+ DMA_InitStruct->DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+
+ /* Initialize the DMA_MemoryInc member */
+ DMA_InitStruct->DMA_MemoryInc = DMA_MemoryInc_Disable;
+
+ /* Initialize the DMA_PeripheralDataSize member */
+ DMA_InitStruct->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+
+ /* Initialize the DMA_MemoryDataSize member */
+ DMA_InitStruct->DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+
+ /* Initialize the DMA_Mode member */
+ DMA_InitStruct->DMA_Mode = DMA_Mode_Normal;
+
+ /* Initialize the DMA_Priority member */
+ DMA_InitStruct->DMA_Priority = DMA_Priority_Low;
+
+ /* Initialize the DMA_M2M member */
+ DMA_InitStruct->DMA_M2M = DMA_M2M_Disable;
+}
+
+/*******************************************************************************
+* Function Name : DMA_Cmd
+* Description : Enables or disables the specified DMAy Channelx.
+* Input : - DMAy_Channelx: where y can be 1 or 2 to select the DMA and
+* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the
+* DMA Channel.
+* - NewState: new state of the DMAy Channelx.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected DMAy Channelx */
+ DMAy_Channelx->CCR |= CCR_ENABLE_Set;
+ }
+ else
+ {
+ /* Disable the selected DMAy Channelx */
+ DMAy_Channelx->CCR &= CCR_ENABLE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : DMA_ITConfig
+* Description : Enables or disables the specified DMAy Channelx interrupts.
+* Input : - DMAy_Channelx: where y can be 1 or 2 to select the DMA and
+* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the
+* DMA Channel.
+* - DMA_IT: specifies the DMA interrupts sources to be enabled
+* or disabled.
+* This parameter can be any combination of the following values:
+* - DMA_IT_TC: Transfer complete interrupt mask
+* - DMA_IT_HT: Half transfer interrupt mask
+* - DMA_IT_TE: Transfer error interrupt mask
+* - NewState: new state of the specified DMA interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, u32 DMA_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+ assert_param(IS_DMA_CONFIG_IT(DMA_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected DMA interrupts */
+ DMAy_Channelx->CCR |= DMA_IT;
+ }
+ else
+ {
+ /* Disable the selected DMA interrupts */
+ DMAy_Channelx->CCR &= ~DMA_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : DMA_GetCurrDataCounter
+* Description : Returns the number of remaining data units in the current
+* DMAy Channelx transfer.
+* Input : - DMAy_Channelx: where y can be 1 or 2 to select the DMA and
+* x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the
+* DMA Channel.
+* Output : None
+* Return : The number of remaining data units in the current DMAy Channelx
+* transfer.
+*******************************************************************************/
+u16 DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx)
+{
+ /* Check the parameters */
+ assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+
+ /* Return the number of remaining data units for DMAy Channelx */
+ return ((u16)(DMAy_Channelx->CNDTR));
+}
+
+/*******************************************************************************
+* Function Name : DMA_GetFlagStatus
+* Description : Checks whether the specified DMAy Channelx flag is set or not.
+* Input : - DMA_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - DMA1_FLAG_GL1: DMA1 Channel1 global flag.
+* - DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag.
+* - DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag.
+* - DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag.
+* - DMA1_FLAG_GL2: DMA1 Channel2 global flag.
+* - DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag.
+* - DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag.
+* - DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag.
+* - DMA1_FLAG_GL3: DMA1 Channel3 global flag.
+* - DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag.
+* - DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag.
+* - DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag.
+* - DMA1_FLAG_GL4: DMA1 Channel4 global flag.
+* - DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag.
+* - DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag.
+* - DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag.
+* - DMA1_FLAG_GL5: DMA1 Channel5 global flag.
+* - DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag.
+* - DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag.
+* - DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag.
+* - DMA1_FLAG_GL6: DMA1 Channel6 global flag.
+* - DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag.
+* - DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag.
+* - DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag.
+* - DMA1_FLAG_GL7: DMA1 Channel7 global flag.
+* - DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag.
+* - DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag.
+* - DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag.
+* - DMA2_FLAG_GL1: DMA2 Channel1 global flag.
+* - DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag.
+* - DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag.
+* - DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag.
+* - DMA2_FLAG_GL2: DMA2 Channel2 global flag.
+* - DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag.
+* - DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag.
+* - DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag.
+* - DMA2_FLAG_GL3: DMA2 Channel3 global flag.
+* - DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag.
+* - DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag.
+* - DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag.
+* - DMA2_FLAG_GL4: DMA2 Channel4 global flag.
+* - DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag.
+* - DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag.
+* - DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag.
+* - DMA2_FLAG_GL5: DMA2 Channel5 global flag.
+* - DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag.
+* - DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag.
+* - DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag.
+* Output : None
+* Return : The new state of DMA_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus DMA_GetFlagStatus(u32 DMA_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_DMA_GET_FLAG(DMA_FLAG));
+
+ /* Calculate the used DMA */
+ if ((DMA_FLAG & FLAG_Mask) != (u32)RESET)
+ {
+ /* Get DMA2 ISR register value */
+ tmpreg = DMA2->ISR ;
+ }
+ else
+ {
+ /* Get DMA1 ISR register value */
+ tmpreg = DMA1->ISR ;
+ }
+
+ /* Check the status of the specified DMA flag */
+ if ((tmpreg & DMA_FLAG) != (u32)RESET)
+ {
+ /* DMA_FLAG is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* DMA_FLAG is reset */
+ bitstatus = RESET;
+ }
+
+ /* Return the DMA_FLAG status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : DMA_ClearFlag
+* Description : Clears the DMAy Channelx's pending flags.
+* Input : - DMA_FLAG: specifies the flag to clear.
+* This parameter can be any combination (for the same DMA) of
+* the following values:
+* - DMA1_FLAG_GL1: DMA1 Channel1 global flag.
+* - DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag.
+* - DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag.
+* - DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag.
+* - DMA1_FLAG_GL2: DMA1 Channel2 global flag.
+* - DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag.
+* - DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag.
+* - DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag.
+* - DMA1_FLAG_GL3: DMA1 Channel3 global flag.
+* - DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag.
+* - DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag.
+* - DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag.
+* - DMA1_FLAG_GL4: DMA1 Channel4 global flag.
+* - DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag.
+* - DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag.
+* - DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag.
+* - DMA1_FLAG_GL5: DMA1 Channel5 global flag.
+* - DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag.
+* - DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag.
+* - DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag.
+* - DMA1_FLAG_GL6: DMA1 Channel6 global flag.
+* - DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag.
+* - DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag.
+* - DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag.
+* - DMA1_FLAG_GL7: DMA1 Channel7 global flag.
+* - DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag.
+* - DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag.
+* - DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag.
+* - DMA2_FLAG_GL1: DMA2 Channel1 global flag.
+* - DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag.
+* - DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag.
+* - DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag.
+* - DMA2_FLAG_GL2: DMA2 Channel2 global flag.
+* - DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag.
+* - DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag.
+* - DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag.
+* - DMA2_FLAG_GL3: DMA2 Channel3 global flag.
+* - DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag.
+* - DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag.
+* - DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag.
+* - DMA2_FLAG_GL4: DMA2 Channel4 global flag.
+* - DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag.
+* - DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag.
+* - DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag.
+* - DMA2_FLAG_GL5: DMA2 Channel5 global flag.
+* - DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag.
+* - DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag.
+* - DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_ClearFlag(u32 DMA_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_DMA_CLEAR_FLAG(DMA_FLAG));
+
+ /* Calculate the used DMA */
+ if ((DMA_FLAG & FLAG_Mask) != (u32)RESET)
+ {
+ /* Clear the selected DMA flags */
+ DMA2->IFCR = DMA_FLAG;
+ }
+ else
+ {
+ /* Clear the selected DMA flags */
+ DMA1->IFCR = DMA_FLAG;
+ }
+}
+
+/*******************************************************************************
+* Function Name : DMA_GetITStatus
+* Description : Checks whether the specified DMAy Channelx interrupt has
+* occurred or not.
+* Input : - DMA_IT: specifies the DMA interrupt source to check.
+* This parameter can be one of the following values:
+* - DMA1_IT_GL1: DMA1 Channel1 global interrupt.
+* - DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt.
+* - DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt.
+* - DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt.
+* - DMA1_IT_GL2: DMA1 Channel2 global interrupt.
+* - DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt.
+* - DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt.
+* - DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt.
+* - DMA1_IT_GL3: DMA1 Channel3 global interrupt.
+* - DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt.
+* - DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt.
+* - DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt.
+* - DMA1_IT_GL4: DMA1 Channel4 global interrupt.
+* - DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt.
+* - DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt.
+* - DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt.
+* - DMA1_IT_GL5: DMA1 Channel5 global interrupt.
+* - DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt.
+* - DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt.
+* - DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt.
+* - DMA1_IT_GL6: DMA1 Channel6 global interrupt.
+* - DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt.
+* - DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt.
+* - DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt.
+* - DMA1_IT_GL7: DMA1 Channel7 global interrupt.
+* - DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt.
+* - DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt.
+* - DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt.
+* - DMA2_IT_GL1: DMA2 Channel1 global interrupt.
+* - DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt.
+* - DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt.
+* - DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt.
+* - DMA2_IT_GL2: DMA2 Channel2 global interrupt.
+* - DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt.
+* - DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt.
+* - DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt.
+* - DMA2_IT_GL3: DMA2 Channel3 global interrupt.
+* - DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt.
+* - DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt.
+* - DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt.
+* - DMA2_IT_GL4: DMA2 Channel4 global interrupt.
+* - DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt.
+* - DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt.
+* - DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt.
+* - DMA2_IT_GL5: DMA2 Channel5 global interrupt.
+* - DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt.
+* - DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt.
+* - DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt.
+* Output : None
+* Return : The new state of DMA_IT (SET or RESET).
+*******************************************************************************/
+ITStatus DMA_GetITStatus(u32 DMA_IT)
+{
+ ITStatus bitstatus = RESET;
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_DMA_GET_IT(DMA_IT));
+
+ /* Calculate the used DMA */
+ if ((DMA_IT & FLAG_Mask) != (u32)RESET)
+ {
+ /* Get DMA2 ISR register value */
+ tmpreg = DMA2->ISR ;
+ }
+ else
+ {
+ /* Get DMA1 ISR register value */
+ tmpreg = DMA1->ISR ;
+ }
+
+ /* Check the status of the specified DMA interrupt */
+ if ((tmpreg & DMA_IT) != (u32)RESET)
+ {
+ /* DMA_IT is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* DMA_IT is reset */
+ bitstatus = RESET;
+ }
+ /* Return the DMA_IT status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : DMA_ClearITPendingBit
+* Description : Clears the DMAy Channelx’s interrupt pending bits.
+* Input : - DMA_IT: specifies the DMA interrupt pending bit to clear.
+* This parameter can be any combination (for the same DMA) of
+* the following values:
+* - DMA1_IT_GL1: DMA1 Channel1 global interrupt.
+* - DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt.
+* - DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt.
+* - DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt.
+* - DMA1_IT_GL2: DMA1 Channel2 global interrupt.
+* - DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt.
+* - DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt.
+* - DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt.
+* - DMA1_IT_GL3: DMA1 Channel3 global interrupt.
+* - DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt.
+* - DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt.
+* - DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt.
+* - DMA1_IT_GL4: DMA1 Channel4 global interrupt.
+* - DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt.
+* - DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt.
+* - DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt.
+* - DMA1_IT_GL5: DMA1 Channel5 global interrupt.
+* - DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt.
+* - DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt.
+* - DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt.
+* - DMA1_IT_GL6: DMA1 Channel6 global interrupt.
+* - DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt.
+* - DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt.
+* - DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt.
+* - DMA1_IT_GL7: DMA1 Channel7 global interrupt.
+* - DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt.
+* - DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt.
+* - DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt.
+* - DMA2_IT_GL1: DMA2 Channel1 global interrupt.
+* - DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt.
+* - DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt.
+* - DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt.
+* - DMA2_IT_GL2: DMA2 Channel2 global interrupt.
+* - DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt.
+* - DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt.
+* - DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt.
+* - DMA2_IT_GL3: DMA2 Channel3 global interrupt.
+* - DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt.
+* - DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt.
+* - DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt.
+* - DMA2_IT_GL4: DMA2 Channel4 global interrupt.
+* - DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt.
+* - DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt.
+* - DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt.
+* - DMA2_IT_GL5: DMA2 Channel5 global interrupt.
+* - DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt.
+* - DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt.
+* - DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt.
+* Output : None
+* Return : None
+*******************************************************************************/
+void DMA_ClearITPendingBit(u32 DMA_IT)
+{
+ /* Check the parameters */
+ assert_param(IS_DMA_CLEAR_IT(DMA_IT));
+
+ /* Calculate the used DMA */
+ if ((DMA_IT & FLAG_Mask) != (u32)RESET)
+ {
+ /* Clear the selected DMA interrupt pending bits */
+ DMA2->IFCR = DMA_IT;
+ }
+ else
+ {
+ /* Clear the selected DMA interrupt pending bits */
+ DMA1->IFCR = DMA_IT;
+ }
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
+
diff --git a/src/stm32lib/src/stm32f10x_exti.c b/src/stm32lib/src/stm32f10x_exti.c new file mode 100644 index 0000000..021a051 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_exti.c @@ -0,0 +1,219 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_exti.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the EXTI firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_exti.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define EXTI_LineNone ((u32)0x00000) /* No interrupt selected */
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : EXTI_DeInit
+* Description : Deinitializes the EXTI peripheral registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_DeInit(void)
+{
+ EXTI->IMR = 0x00000000;
+ EXTI->EMR = 0x00000000;
+ EXTI->RTSR = 0x00000000;
+ EXTI->FTSR = 0x00000000;
+ EXTI->PR = 0x0007FFFF;
+}
+
+/*******************************************************************************
+* Function Name : EXTI_Init
+* Description : Initializes the EXTI peripheral according to the specified
+* parameters in the EXTI_InitStruct.
+* Input : - EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure
+* that contains the configuration information for the EXTI
+* peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_EXTI_MODE(EXTI_InitStruct->EXTI_Mode));
+ assert_param(IS_EXTI_TRIGGER(EXTI_InitStruct->EXTI_Trigger));
+ assert_param(IS_EXTI_LINE(EXTI_InitStruct->EXTI_Line));
+ assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->EXTI_LineCmd));
+
+ if (EXTI_InitStruct->EXTI_LineCmd != DISABLE)
+ {
+ /* Clear EXTI line configuration */
+ EXTI->IMR &= ~EXTI_InitStruct->EXTI_Line;
+ EXTI->EMR &= ~EXTI_InitStruct->EXTI_Line;
+
+ *(vu32 *)(EXTI_BASE + (u32)EXTI_InitStruct->EXTI_Mode)|= EXTI_InitStruct->EXTI_Line;
+
+ /* Clear Rising Falling edge configuration */
+ EXTI->RTSR &= ~EXTI_InitStruct->EXTI_Line;
+ EXTI->FTSR &= ~EXTI_InitStruct->EXTI_Line;
+
+ /* Select the trigger for the selected external interrupts */
+ if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling)
+ {
+ /* Rising Falling edge */
+ EXTI->RTSR |= EXTI_InitStruct->EXTI_Line;
+ EXTI->FTSR |= EXTI_InitStruct->EXTI_Line;
+ }
+ else
+ {
+ *(vu32 *)(EXTI_BASE + (u32)EXTI_InitStruct->EXTI_Trigger)|= EXTI_InitStruct->EXTI_Line;
+ }
+ }
+ else
+ {
+ /* Disable the selected external lines */
+ *(vu32 *)(EXTI_BASE + (u32)EXTI_InitStruct->EXTI_Mode)&= ~EXTI_InitStruct->EXTI_Line;
+ }
+}
+
+/*******************************************************************************
+* Function Name : EXTI_StructInit
+* Description : Fills each EXTI_InitStruct member with its reset value.
+* Input : - EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct)
+{
+ EXTI_InitStruct->EXTI_Line = EXTI_LineNone;
+ EXTI_InitStruct->EXTI_Mode = EXTI_Mode_Interrupt;
+ EXTI_InitStruct->EXTI_Trigger = EXTI_Trigger_Falling;
+ EXTI_InitStruct->EXTI_LineCmd = DISABLE;
+}
+
+/*******************************************************************************
+* Function Name : EXTI_GenerateSWInterrupt
+* Description : Generates a Software interrupt.
+* Input : - EXTI_Line: specifies the EXTI lines to be enabled or
+* disabled.
+* This parameter can be any combination of EXTI_Linex where
+* x can be (0..18).
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_GenerateSWInterrupt(u32 EXTI_Line)
+{
+ /* Check the parameters */
+ assert_param(IS_EXTI_LINE(EXTI_Line));
+
+ EXTI->SWIER |= EXTI_Line;
+}
+
+/*******************************************************************************
+* Function Name : EXTI_GetFlagStatus
+* Description : Checks whether the specified EXTI line flag is set or not.
+* Input : - EXTI_Line: specifies the EXTI line flag to check.
+* This parameter can be:
+* - EXTI_Linex: External interrupt line x where x(0..18)
+* Output : None
+* Return : The new state of EXTI_Line (SET or RESET).
+*******************************************************************************/
+FlagStatus EXTI_GetFlagStatus(u32 EXTI_Line)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_GET_EXTI_LINE(EXTI_Line));
+
+ if ((EXTI->PR & EXTI_Line) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : EXTI_ClearFlag
+* Description : Clears the EXTI’s line pending flags.
+* Input : - EXTI_Line: specifies the EXTI lines flags to clear.
+* This parameter can be any combination of EXTI_Linex where
+* x can be (0..18).
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_ClearFlag(u32 EXTI_Line)
+{
+ /* Check the parameters */
+ assert_param(IS_EXTI_LINE(EXTI_Line));
+
+ EXTI->PR = EXTI_Line;
+}
+
+/*******************************************************************************
+* Function Name : EXTI_GetITStatus
+* Description : Checks whether the specified EXTI line is asserted or not.
+* Input : - EXTI_Line: specifies the EXTI line to check.
+* This parameter can be:
+* - EXTI_Linex: External interrupt line x where x(0..18)
+* Output : None
+* Return : The new state of EXTI_Line (SET or RESET).
+*******************************************************************************/
+ITStatus EXTI_GetITStatus(u32 EXTI_Line)
+{
+ ITStatus bitstatus = RESET;
+ u32 enablestatus = 0;
+
+ /* Check the parameters */
+ assert_param(IS_GET_EXTI_LINE(EXTI_Line));
+
+ enablestatus = EXTI->IMR & EXTI_Line;
+
+ if (((EXTI->PR & EXTI_Line) != (u32)RESET) && (enablestatus != (u32)RESET))
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : EXTI_ClearITPendingBit
+* Description : Clears the EXTI’s line pending bits.
+* Input : - EXTI_Line: specifies the EXTI lines to clear.
+* This parameter can be any combination of EXTI_Linex where
+* x can be (0..18).
+* Output : None
+* Return : None
+*******************************************************************************/
+void EXTI_ClearITPendingBit(u32 EXTI_Line)
+{
+ /* Check the parameters */
+ assert_param(IS_EXTI_LINE(EXTI_Line));
+
+ EXTI->PR = EXTI_Line;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_flash.c b/src/stm32lib/src/stm32f10x_flash.c new file mode 100644 index 0000000..66952f2 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_flash.c @@ -0,0 +1,916 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_flash.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the FLASH firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_flash.h"
+void test(u32 x) {
+ int y;
+ x = 1;
+ y = x;
+}
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Flash Access Control Register bits */
+#define ACR_LATENCY_Mask ((u32)0x00000038)
+#define ACR_HLFCYA_Mask ((u32)0xFFFFFFF7)
+#define ACR_PRFTBE_Mask ((u32)0xFFFFFFEF)
+
+#ifdef _FLASH_PROG
+/* Flash Access Control Register bits */
+#define ACR_PRFTBS_Mask ((u32)0x00000020)
+
+/* Flash Control Register bits */
+#define CR_PG_Set ((u32)0x00000001)
+#define CR_PG_Reset ((u32)0x00001FFE)
+
+#define CR_PER_Set ((u32)0x00000002)
+#define CR_PER_Reset ((u32)0x00001FFD)
+
+#define CR_MER_Set ((u32)0x00000004)
+#define CR_MER_Reset ((u32)0x00001FFB)
+
+#define CR_OPTPG_Set ((u32)0x00000010)
+#define CR_OPTPG_Reset ((u32)0x00001FEF)
+
+#define CR_OPTER_Set ((u32)0x00000020)
+#define CR_OPTER_Reset ((u32)0x00001FDF)
+
+#define CR_STRT_Set ((u32)0x00000040)
+
+#define CR_LOCK_Set ((u32)0x00000080)
+
+/* FLASH Mask */
+#define RDPRT_Mask ((u32)0x00000002)
+#define WRP0_Mask ((u32)0x000000FF)
+#define WRP1_Mask ((u32)0x0000FF00)
+#define WRP2_Mask ((u32)0x00FF0000)
+#define WRP3_Mask ((u32)0xFF000000)
+
+/* FLASH Keys */
+#define RDP_Key ((u16)0x00A5)
+#define FLASH_KEY1 ((u32)0x45670123)
+#define FLASH_KEY2 ((u32)0xCDEF89AB)
+
+/* Delay definition */
+#define EraseTimeout ((u32)0x00000FFF)
+#define ProgramTimeout ((u32)0x0000000F)
+#endif
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+#ifdef _FLASH_PROG
+static void delay(void);
+#endif
+
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : FLASH_SetLatency
+* Description : Sets the code latency value.
+* Input : - FLASH_Latency: specifies the FLASH Latency value.
+* This parameter can be one of the following values:
+* - FLASH_Latency_0: FLASH Zero Latency cycle
+* - FLASH_Latency_1: FLASH One Latency cycle
+* - FLASH_Latency_2: FLASH Two Latency cycles
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_SetLatency(u32 FLASH_Latency)
+{
+ /* Check the parameters */
+ assert_param(IS_FLASH_LATENCY(FLASH_Latency));
+
+ /* Sets the Latency value */
+ FLASH->ACR &= ACR_LATENCY_Mask;
+ FLASH->ACR |= FLASH_Latency;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_HalfCycleAccessCmd
+* Description : Enables or disables the Half cycle flash access.
+* Input : - FLASH_HalfCycle: specifies the FLASH Half cycle Access mode.
+* This parameter can be one of the following values:
+* - FLASH_HalfCycleAccess_Enable: FLASH Half Cycle Enable
+* - FLASH_HalfCycleAccess_Disable: FLASH Half Cycle Disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_HalfCycleAccessCmd(u32 FLASH_HalfCycleAccess)
+{
+ /* Check the parameters */
+ assert_param(IS_FLASH_HALFCYCLEACCESS_STATE(FLASH_HalfCycleAccess));
+
+ /* Enable or disable the Half cycle access */
+ FLASH->ACR &= ACR_HLFCYA_Mask;
+ FLASH->ACR |= FLASH_HalfCycleAccess;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_PrefetchBufferCmd
+* Description : Enables or disables the Prefetch Buffer.
+* Input : - FLASH_PrefetchBuffer: specifies the Prefetch buffer status.
+* This parameter can be one of the following values:
+* - FLASH_PrefetchBuffer_Enable: FLASH Prefetch Buffer Enable
+* - FLASH_PrefetchBuffer_Disable: FLASH Prefetch Buffer Disable
+* Output : None
+* Return : None
+*******************************************************************************/
+
+void FLASH_PrefetchBufferCmd(u32 FLASH_PrefetchBuffer)
+{
+ /* Check the parameters */
+ assert_param(IS_FLASH_PREFETCHBUFFER_STATE(FLASH_PrefetchBuffer));
+
+ /* Enable or disable the Prefetch Buffer */
+ FLASH->ACR &= ACR_PRFTBE_Mask;
+ FLASH->ACR |= FLASH_PrefetchBuffer;
+}
+
+#ifdef _FLASH_PROG
+/*******************************************************************************
+* Function Name : FLASH_Unlock
+* Description : Unlocks the FLASH Program Erase Controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_Unlock(void)
+{
+ /* Authorize the FPEC Access */
+ FLASH->KEYR = FLASH_KEY1;
+ FLASH->KEYR = FLASH_KEY2;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_Lock
+* Description : Locks the FLASH Program Erase Controller.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_Lock(void)
+{
+ /* Set the Lock Bit to lock the FPEC and the FCR */
+ FLASH->CR |= CR_LOCK_Set;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_ErasePage
+* Description : Erases a specified FLASH page.
+* Input : - Page_Address: The page address to be erased.
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_ErasePage(u32 Page_Address)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_ADDRESS(Page_Address));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the previous operation is completed, proceed to erase the page */
+ FLASH->CR|= CR_PER_Set;
+ FLASH->AR = Page_Address;
+ FLASH->CR|= CR_STRT_Set;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the erase operation is completed, disable the PER Bit */
+ FLASH->CR &= CR_PER_Reset;
+ }
+ }
+ /* Return the Erase Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_EraseAllPages
+* Description : Erases all FLASH pages.
+* Input : None
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_EraseAllPages(void)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the previous operation is completed, proceed to erase all pages */
+ FLASH->CR |= CR_MER_Set;
+ FLASH->CR |= CR_STRT_Set;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the erase operation is completed, disable the MER Bit */
+ FLASH->CR &= CR_MER_Reset;
+ }
+ }
+ /* Return the Erase Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_EraseOptionBytes
+* Description : Erases the FLASH option bytes.
+* Input : None
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_EraseOptionBytes(void)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* Authorize the small information block programming */
+ FLASH->OPTKEYR = FLASH_KEY1;
+ FLASH->OPTKEYR = FLASH_KEY2;
+
+ /* if the previous operation is completed, proceed to erase the option bytes */
+ FLASH->CR |= CR_OPTER_Set;
+ FLASH->CR |= CR_STRT_Set;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the erase operation is completed, disable the OPTER Bit */
+ FLASH->CR &= CR_OPTER_Reset;
+
+ /* Enable the Option Bytes Programming operation */
+ FLASH->CR |= CR_OPTPG_Set;
+
+ /* Enable the readout access */
+ OB->RDP= RDP_Key;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the program operation is completed, disable the OPTPG Bit */
+ FLASH->CR &= CR_OPTPG_Reset;
+ }
+ }
+ else
+ {
+ if (status != FLASH_BUSY)
+ {
+ /* Disable the OPTPG Bit */
+ FLASH->CR &= CR_OPTPG_Reset;
+ }
+ }
+ }
+ /* Return the erase status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_ProgramWord
+* Description : Programs a word at a specified address.
+* Input : - Address: specifies the address to be programmed.
+* - Data: specifies the data to be programmed.
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_ProgramWord(u32 Address, u32 Data)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_ADDRESS(Address));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the previous operation is completed, proceed to program the new first
+ half word */
+ FLASH->CR |= CR_PG_Set;
+
+ *(vu16*)Address = (u16)Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the previous operation is completed, proceed to program the new second
+ half word */
+ *(vu16*)(Address + 2) = Data >> 16;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* Disable the PG Bit */
+ FLASH->CR &= CR_PG_Reset;
+ }
+ }
+ else
+ {
+ if (status != FLASH_BUSY)
+ {
+ /* Disable the PG Bit */
+ FLASH->CR &= CR_PG_Reset;
+ }
+ }
+ }
+ /* Return the Program Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_ProgramHalfWord
+* Description : Programs a half word at a specified address.
+* Input : - Address: specifies the address to be programmed.
+* - Data: specifies the data to be programmed.
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_ProgramHalfWord(u32 Address, u16 Data)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_ADDRESS(Address));
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the previous operation is completed, proceed to program the new data */
+ FLASH->CR |= CR_PG_Set;
+
+ *(vu16*)Address = Data;
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the program operation is completed, disable the PG Bit */
+ FLASH->CR &= CR_PG_Reset;
+ }
+ }
+ /* Return the Program Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_ProgramOptionByteData
+* Description : Programs a half word at a specified Option Byte Data address.
+* Input : - Address: specifies the address to be programmed.
+* This parameter can be 0x1FFFF804 or 0x1FFFF806.
+* - Data: specifies the data to be programmed.
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_ProgramOptionByteData(u32 Address, u8 Data)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check the parameters */
+ assert_param(IS_OB_DATA_ADDRESS(Address));
+
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* Authorize the small information block programming */
+ FLASH->OPTKEYR = FLASH_KEY1;
+ FLASH->OPTKEYR = FLASH_KEY2;
+
+ /* Enables the Option Bytes Programming operation */
+ FLASH->CR |= CR_OPTPG_Set;
+ *(vu16*)Address = Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the program operation is completed, disable the OPTPG Bit */
+ FLASH->CR &= CR_OPTPG_Reset;
+ }
+ }
+ /* Return the Option Byte Data Program Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_EnableWriteProtection
+* Description : Write protects the desired pages
+* Input : - FLASH_Pages: specifies the address of the pages to be
+* write protected. This parameter can be:
+* - For STM32F10Xxx Medium-density devices (FLASH page size equal to 1 KB)
+* - A value between FLASH_WRProt_Pages0to3 and
+* FLASH_WRProt_Pages124to127
+* - For STM32F10Xxx High-density devices (FLASH page size equal to 2 KB)
+* - A value between FLASH_WRProt_Pages0to1 and
+* FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to255
+* - FLASH_WRProt_AllPages
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_EnableWriteProtection(u32 FLASH_Pages)
+{
+ u16 WRP0_Data = 0xFFFF, WRP1_Data = 0xFFFF, WRP2_Data = 0xFFFF, WRP3_Data = 0xFFFF;
+
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_WRPROT_PAGE(FLASH_Pages));
+
+ FLASH_Pages = (u32)(~FLASH_Pages);
+ WRP0_Data = (vu16)(FLASH_Pages & WRP0_Mask);
+ WRP1_Data = (vu16)((FLASH_Pages & WRP1_Mask) >> 8);
+ WRP2_Data = (vu16)((FLASH_Pages & WRP2_Mask) >> 16);
+ WRP3_Data = (vu16)((FLASH_Pages & WRP3_Mask) >> 24);
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* Authorizes the small information block programming */
+ FLASH->OPTKEYR = FLASH_KEY1;
+ FLASH->OPTKEYR = FLASH_KEY2;
+ FLASH->CR |= CR_OPTPG_Set;
+
+ if(WRP0_Data != 0xFF)
+ {
+ OB->WRP0 = WRP0_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+ }
+ if((status == FLASH_COMPLETE) && (WRP1_Data != 0xFF))
+ {
+ OB->WRP1 = WRP1_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+ }
+
+ if((status == FLASH_COMPLETE) && (WRP2_Data != 0xFF))
+ {
+ OB->WRP2 = WRP2_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+ }
+
+ if((status == FLASH_COMPLETE)&& (WRP3_Data != 0xFF))
+ {
+ OB->WRP3 = WRP3_Data;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+ }
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the program operation is completed, disable the OPTPG Bit */
+ FLASH->CR &= CR_OPTPG_Reset;
+ }
+ }
+ /* Return the write protection operation Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_ReadOutProtection
+* Description : Enables or disables the read out protection.
+* If the user has already programmed the other option bytes before
+* calling this function, he must re-program them since this
+* function erases all option bytes.
+* Input : - Newstate: new state of the ReadOut Protection.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* Authorizes the small information block programming */
+ FLASH->OPTKEYR = FLASH_KEY1;
+ FLASH->OPTKEYR = FLASH_KEY2;
+
+ FLASH->CR |= CR_OPTER_Set;
+ FLASH->CR |= CR_STRT_Set;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* if the erase operation is completed, disable the OPTER Bit */
+ FLASH->CR &= CR_OPTER_Reset;
+
+ /* Enable the Option Bytes Programming operation */
+ FLASH->CR |= CR_OPTPG_Set;
+
+ if(NewState != DISABLE)
+ {
+ OB->RDP = 0x00;
+ }
+ else
+ {
+ OB->RDP = RDP_Key;
+ }
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(EraseTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the program operation is completed, disable the OPTPG Bit */
+ FLASH->CR &= CR_OPTPG_Reset;
+ }
+ }
+ else
+ {
+ if(status != FLASH_BUSY)
+ {
+ /* Disable the OPTER Bit */
+ FLASH->CR &= CR_OPTER_Reset;
+ }
+ }
+ }
+ /* Return the protection operation Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_UserOptionByteConfig
+* Description : Programs the FLASH User Option Byte: IWDG_SW / RST_STOP /
+* RST_STDBY.
+* Input : - OB_IWDG: Selects the IWDG mode
+* This parameter can be one of the following values:
+* - OB_IWDG_SW: Software IWDG selected
+* - OB_IWDG_HW: Hardware IWDG selected
+* - OB_STOP: Reset event when entering STOP mode.
+* This parameter can be one of the following values:
+* - OB_STOP_NoRST: No reset generated when entering in STOP
+* - OB_STOP_RST: Reset generated when entering in STOP
+* - OB_STDBY: Reset event when entering Standby mode.
+* This parameter can be one of the following values:
+* - OB_STDBY_NoRST: No reset generated when entering in STANDBY
+* - OB_STDBY_RST: Reset generated when entering in STANDBY
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_UserOptionByteConfig(u16 OB_IWDG, u16 OB_STOP, u16 OB_STDBY)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check the parameters */
+ assert_param(IS_OB_IWDG_SOURCE(OB_IWDG));
+ assert_param(IS_OB_STOP_SOURCE(OB_STOP));
+ assert_param(IS_OB_STDBY_SOURCE(OB_STDBY));
+
+ /* Authorize the small information block programming */
+ FLASH->OPTKEYR = FLASH_KEY1;
+ FLASH->OPTKEYR = FLASH_KEY2;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status == FLASH_COMPLETE)
+ {
+ /* Enable the Option Bytes Programming operation */
+ FLASH->CR |= CR_OPTPG_Set;
+
+ OB->USER = ( OB_IWDG | OB_STOP |OB_STDBY) | (u16)0xF8;
+
+ /* Wait for last operation to be completed */
+ status = FLASH_WaitForLastOperation(ProgramTimeout);
+
+ if(status != FLASH_BUSY)
+ {
+ /* if the program operation is completed, disable the OPTPG Bit */
+ FLASH->CR &= CR_OPTPG_Reset;
+ }
+ }
+ /* Return the Option Byte program Status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_GetUserOptionByte
+* Description : Returns the FLASH User Option Bytes values.
+* Input : None
+* Output : None
+* Return : The FLASH User Option Bytes values:IWDG_SW(Bit0), RST_STOP(Bit1)
+* and RST_STDBY(Bit2).
+*******************************************************************************/
+u32 FLASH_GetUserOptionByte(void)
+{
+ /* Return the User Option Byte */
+ return (u32)(FLASH->OBR >> 2);
+}
+
+/*******************************************************************************
+* Function Name : FLASH_GetWriteProtectionOptionByte
+* Description : Returns the FLASH Write Protection Option Bytes Register value.
+* Input : None
+* Output : None
+* Return : The FLASH Write Protection Option Bytes Register value
+*******************************************************************************/
+u32 FLASH_GetWriteProtectionOptionByte(void)
+{
+ /* Return the Falsh write protection Register value */
+ return (u32)(FLASH->WRPR);
+}
+
+/*******************************************************************************
+* Function Name : FLASH_GetReadOutProtectionStatus
+* Description : Checks whether the FLASH Read Out Protection Status is set
+* or not.
+* Input : None
+* Output : None
+* Return : FLASH ReadOut Protection Status(SET or RESET)
+*******************************************************************************/
+FlagStatus FLASH_GetReadOutProtectionStatus(void)
+{
+ FlagStatus readoutstatus = RESET;
+
+ if ((FLASH->OBR & RDPRT_Mask) != (u32)RESET)
+ {
+ readoutstatus = SET;
+ }
+ else
+ {
+ readoutstatus = RESET;
+ }
+ return readoutstatus;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_GetPrefetchBufferStatus
+* Description : Checks whether the FLASH Prefetch Buffer status is set or not.
+* Input : None
+* Output : None
+* Return : FLASH Prefetch Buffer Status (SET or RESET).
+*******************************************************************************/
+FlagStatus FLASH_GetPrefetchBufferStatus(void)
+{
+ FlagStatus bitstatus = RESET;
+
+ if ((FLASH->ACR & ACR_PRFTBS_Mask) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ /* Return the new state of FLASH Prefetch Buffer Status (SET or RESET) */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_ITConfig
+* Description : Enables or disables the specified FLASH interrupts.
+* Input : - FLASH_IT: specifies the FLASH interrupt sources to be
+* enabled or disabled.
+* This parameter can be any combination of the following values:
+* - FLASH_IT_ERROR: FLASH Error Interrupt
+* - FLASH_IT_EOP: FLASH end of operation Interrupt
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_ITConfig(u16 FLASH_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FLASH_IT(FLASH_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if(NewState != DISABLE)
+ {
+ /* Enable the interrupt sources */
+ FLASH->CR |= FLASH_IT;
+ }
+ else
+ {
+ /* Disable the interrupt sources */
+ FLASH->CR &= ~(u32)FLASH_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FLASH_GetFlagStatus
+* Description : Checks whether the specified FLASH flag is set or not.
+* Input : - FLASH_FLAG: specifies the FLASH flag to check.
+* This parameter can be one of the following values:
+* - FLASH_FLAG_BSY: FLASH Busy flag
+* - FLASH_FLAG_PGERR: FLASH Program error flag
+* - FLASH_FLAG_WRPRTERR: FLASH Write protected error flag
+* - FLASH_FLAG_EOP: FLASH End of Operation flag
+* - FLASH_FLAG_OPTERR: FLASH Option Byte error flag
+* Output : None
+* Return : The new state of FLASH_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus FLASH_GetFlagStatus(u16 FLASH_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG)) ;
+
+ if(FLASH_FLAG == FLASH_FLAG_OPTERR)
+ {
+ if((FLASH->OBR & FLASH_FLAG_OPTERR) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ }
+ else
+ {
+ if((FLASH->SR & FLASH_FLAG) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ }
+ /* Return the new state of FLASH_FLAG (SET or RESET) */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_ClearFlag
+* Description : Clears the FLASH’s pending flags.
+* Input : - FLASH_FLAG: specifies the FLASH flags to clear.
+* This parameter can be any combination of the following values:
+* - FLASH_FLAG_BSY: FLASH Busy flag
+* - FLASH_FLAG_PGERR: FLASH Program error flag
+* - FLASH_FLAG_WRPRTERR: FLASH Write protected error flag
+* - FLASH_FLAG_EOP: FLASH End of Operation flag
+* Output : None
+* Return : None
+*******************************************************************************/
+void FLASH_ClearFlag(u16 FLASH_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG)) ;
+
+ /* Clear the flags */
+ FLASH->SR = FLASH_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_GetStatus
+* Description : Returns the FLASH Status.
+* Input : None
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP or FLASH_COMPLETE
+*******************************************************************************/
+FLASH_Status FLASH_GetStatus(void)
+{
+ FLASH_Status flashstatus = FLASH_COMPLETE;
+
+ if((FLASH->SR & FLASH_FLAG_BSY) == FLASH_FLAG_BSY)
+ {
+ flashstatus = FLASH_BUSY;
+ }
+ else
+ {
+ if(FLASH->SR & FLASH_FLAG_PGERR)
+ {
+ flashstatus = FLASH_ERROR_PG;
+ }
+ else
+ {
+ if(FLASH->SR & FLASH_FLAG_WRPRTERR)
+ {
+ flashstatus = FLASH_ERROR_WRP;
+ }
+ else
+ {
+ flashstatus = FLASH_COMPLETE;
+ }
+ }
+ }
+ /* Return the Flash Status */
+ return flashstatus;
+}
+
+/*******************************************************************************
+* Function Name : FLASH_WaitForLastOperation
+* Description : Waits for a Flash operation to complete or a TIMEOUT to occur.
+* Input : - Timeout: FLASH progamming Timeout
+* Output : None
+* Return : FLASH Status: The returned value can be: FLASH_BUSY,
+* FLASH_ERROR_PG, FLASH_ERROR_WRP, FLASH_COMPLETE or
+* FLASH_TIMEOUT.
+*******************************************************************************/
+FLASH_Status FLASH_WaitForLastOperation(u32 Timeout)
+{
+ FLASH_Status status = FLASH_COMPLETE;
+
+ /* Check for the Flash Status */
+ status = FLASH_GetStatus();
+
+ /* Wait for a Flash operation to complete or a TIMEOUT to occur */
+ while((status == FLASH_BUSY) && (Timeout != 0x00))
+ {
+ delay();
+ status = FLASH_GetStatus();
+ Timeout--;
+ }
+
+ if(Timeout == 0x00 )
+ {
+ status = FLASH_TIMEOUT;
+ }
+
+ /* Return the operation status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : delay
+* Description : Inserts a time delay.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+static void delay(void)
+{
+ vu32 i = 0;
+
+ for(i = 0xFF; i != 0; i--)
+ {
+ }
+}
+#endif
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_flash.lst b/src/stm32lib/src/stm32f10x_flash.lst new file mode 100644 index 0000000..37ad356 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_flash.lst @@ -0,0 +1,267 @@ + 1 .syntax unified + 2 .cpu cortex-m3 + 3 .fpu softvfp + 4 .eabi_attribute 20, 1 + 5 .eabi_attribute 21, 1 + 6 .eabi_attribute 23, 3 + 7 .eabi_attribute 24, 1 + 8 .eabi_attribute 25, 1 + 9 .eabi_attribute 26, 1 + 10 .eabi_attribute 30, 4 + 11 .eabi_attribute 18, 4 + 12 .thumb + 13 .file "stm32f10x_flash.c" + 21 .Ltext0: + 22 .align 2 + 23 .global test + 24 .thumb + 25 .thumb_func + 27 test: + 28 .LFB23: + 29 .file 1 "stm32lib/src/stm32f10x_flash.c" + 1:stm32lib/src/stm32f10x_flash.c **** /******************** (C) COPYRIGHT 2008 STMicroelectronics ******************** + 2:stm32lib/src/stm32f10x_flash.c **** * File Name : stm32f10x_flash.c + 3:stm32lib/src/stm32f10x_flash.c **** * Author : MCD Application Team + 4:stm32lib/src/stm32f10x_flash.c **** * Version : V2.0.2 + 5:stm32lib/src/stm32f10x_flash.c **** * Date : 07/11/2008 + 6:stm32lib/src/stm32f10x_flash.c **** * Description : This file provides all the FLASH firmware functions. + 7:stm32lib/src/stm32f10x_flash.c **** ******************************************************************************** + 8:stm32lib/src/stm32f10x_flash.c **** * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + 9:stm32lib/src/stm32f10x_flash.c **** * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. + 10:stm32lib/src/stm32f10x_flash.c **** * AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, + 11:stm32lib/src/stm32f10x_flash.c **** * INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE + 12:stm32lib/src/stm32f10x_flash.c **** * CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING + 13:stm32lib/src/stm32f10x_flash.c **** * INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + 14:stm32lib/src/stm32f10x_flash.c **** *******************************************************************************/ + 15:stm32lib/src/stm32f10x_flash.c **** + 16:stm32lib/src/stm32f10x_flash.c **** /* Includes ------------------------------------------------------------------*/ + 17:stm32lib/src/stm32f10x_flash.c **** #include "stm32f10x_flash.h" + 18:stm32lib/src/stm32f10x_flash.c **** void test(u32 x) { + 30 .loc 1 18 0 + 31 @ args = 0, pretend = 0, frame = 0 + 32 @ frame_needed = 0, uses_anonymous_args = 0 + 33 @ link register save eliminated. + 34 .LVL0: + 19:stm32lib/src/stm32f10x_flash.c **** int y; + 20:stm32lib/src/stm32f10x_flash.c **** x = 1; + 21:stm32lib/src/stm32f10x_flash.c **** y = x; + 22:stm32lib/src/stm32f10x_flash.c **** } + 35 .loc 1 22 0 + 36 0000 7047 bx lr + 37 .LFE23: + 39 0002 00BF .align 2 + 40 .global FLASH_SetLatency + 41 .thumb + 42 .thumb_func + 44 FLASH_SetLatency: + 45 .LFB24: + 23:stm32lib/src/stm32f10x_flash.c **** /* Private typedef -----------------------------------------------------------*/ + 24:stm32lib/src/stm32f10x_flash.c **** /* Private define ------------------------------------------------------------*/ + 25:stm32lib/src/stm32f10x_flash.c **** /* Flash Access Control Register bits */ + 26:stm32lib/src/stm32f10x_flash.c **** #define ACR_LATENCY_Mask ((u32)0x00000038) + 27:stm32lib/src/stm32f10x_flash.c **** #define ACR_HLFCYA_Mask ((u32)0xFFFFFFF7) + 28:stm32lib/src/stm32f10x_flash.c **** #define ACR_PRFTBE_Mask ((u32)0xFFFFFFEF) + 29:stm32lib/src/stm32f10x_flash.c **** + 30:stm32lib/src/stm32f10x_flash.c **** #ifdef _FLASH_PROG + 31:stm32lib/src/stm32f10x_flash.c **** /* Flash Access Control Register bits */ + 32:stm32lib/src/stm32f10x_flash.c **** #define ACR_PRFTBS_Mask ((u32)0x00000020) + 33:stm32lib/src/stm32f10x_flash.c **** + 34:stm32lib/src/stm32f10x_flash.c **** /* Flash Control Register bits */ + 35:stm32lib/src/stm32f10x_flash.c **** #define CR_PG_Set ((u32)0x00000001) + 36:stm32lib/src/stm32f10x_flash.c **** #define CR_PG_Reset ((u32)0x00001FFE) + 37:stm32lib/src/stm32f10x_flash.c **** + 38:stm32lib/src/stm32f10x_flash.c **** #define CR_PER_Set ((u32)0x00000002) + 39:stm32lib/src/stm32f10x_flash.c **** #define CR_PER_Reset ((u32)0x00001FFD) + 40:stm32lib/src/stm32f10x_flash.c **** + 41:stm32lib/src/stm32f10x_flash.c **** #define CR_MER_Set ((u32)0x00000004) + 42:stm32lib/src/stm32f10x_flash.c **** #define CR_MER_Reset ((u32)0x00001FFB) + 43:stm32lib/src/stm32f10x_flash.c **** + 44:stm32lib/src/stm32f10x_flash.c **** #define CR_OPTPG_Set ((u32)0x00000010) + 45:stm32lib/src/stm32f10x_flash.c **** #define CR_OPTPG_Reset ((u32)0x00001FEF) + 46:stm32lib/src/stm32f10x_flash.c **** + 47:stm32lib/src/stm32f10x_flash.c **** #define CR_OPTER_Set ((u32)0x00000020) + 48:stm32lib/src/stm32f10x_flash.c **** #define CR_OPTER_Reset ((u32)0x00001FDF) + 49:stm32lib/src/stm32f10x_flash.c **** + 50:stm32lib/src/stm32f10x_flash.c **** #define CR_STRT_Set ((u32)0x00000040) + 51:stm32lib/src/stm32f10x_flash.c **** + 52:stm32lib/src/stm32f10x_flash.c **** #define CR_LOCK_Set ((u32)0x00000080) + 53:stm32lib/src/stm32f10x_flash.c **** + 54:stm32lib/src/stm32f10x_flash.c **** /* FLASH Mask */ + 55:stm32lib/src/stm32f10x_flash.c **** #define RDPRT_Mask ((u32)0x00000002) + 56:stm32lib/src/stm32f10x_flash.c **** #define WRP0_Mask ((u32)0x000000FF) + 57:stm32lib/src/stm32f10x_flash.c **** #define WRP1_Mask ((u32)0x0000FF00) + 58:stm32lib/src/stm32f10x_flash.c **** #define WRP2_Mask ((u32)0x00FF0000) + 59:stm32lib/src/stm32f10x_flash.c **** #define WRP3_Mask ((u32)0xFF000000) + 60:stm32lib/src/stm32f10x_flash.c **** + 61:stm32lib/src/stm32f10x_flash.c **** /* FLASH Keys */ + 62:stm32lib/src/stm32f10x_flash.c **** #define RDP_Key ((u16)0x00A5) + 63:stm32lib/src/stm32f10x_flash.c **** #define FLASH_KEY1 ((u32)0x45670123) + 64:stm32lib/src/stm32f10x_flash.c **** #define FLASH_KEY2 ((u32)0xCDEF89AB) + 65:stm32lib/src/stm32f10x_flash.c **** + 66:stm32lib/src/stm32f10x_flash.c **** /* Delay definition */ + 67:stm32lib/src/stm32f10x_flash.c **** #define EraseTimeout ((u32)0x00000FFF) + 68:stm32lib/src/stm32f10x_flash.c **** #define ProgramTimeout ((u32)0x0000000F) + 69:stm32lib/src/stm32f10x_flash.c **** #endif + 70:stm32lib/src/stm32f10x_flash.c **** + 71:stm32lib/src/stm32f10x_flash.c **** /* Private macro -------------------------------------------------------------*/ + 72:stm32lib/src/stm32f10x_flash.c **** /* Private variables ---------------------------------------------------------*/ + 73:stm32lib/src/stm32f10x_flash.c **** /* Private function prototypes -----------------------------------------------*/ + 74:stm32lib/src/stm32f10x_flash.c **** #ifdef _FLASH_PROG + 75:stm32lib/src/stm32f10x_flash.c **** static void delay(void); + 76:stm32lib/src/stm32f10x_flash.c **** #endif + 77:stm32lib/src/stm32f10x_flash.c **** + 78:stm32lib/src/stm32f10x_flash.c **** /* Private functions ---------------------------------------------------------*/ + 79:stm32lib/src/stm32f10x_flash.c **** /******************************************************************************* + 80:stm32lib/src/stm32f10x_flash.c **** * Function Name : FLASH_SetLatency + 81:stm32lib/src/stm32f10x_flash.c **** * Description : Sets the code latency value. + 82:stm32lib/src/stm32f10x_flash.c **** * Input : - FLASH_Latency: specifies the FLASH Latency value. + 83:stm32lib/src/stm32f10x_flash.c **** * This parameter can be one of the following values: + 84:stm32lib/src/stm32f10x_flash.c **** * - FLASH_Latency_0: FLASH Zero Latency cycle + 85:stm32lib/src/stm32f10x_flash.c **** * - FLASH_Latency_1: FLASH One Latency cycle + 86:stm32lib/src/stm32f10x_flash.c **** * - FLASH_Latency_2: FLASH Two Latency cycles + 87:stm32lib/src/stm32f10x_flash.c **** * Output : None + 88:stm32lib/src/stm32f10x_flash.c **** * Return : None + 89:stm32lib/src/stm32f10x_flash.c **** *******************************************************************************/ + 90:stm32lib/src/stm32f10x_flash.c **** void FLASH_SetLatency(u32 FLASH_Latency) + 91:stm32lib/src/stm32f10x_flash.c **** { + 46 .loc 1 91 0 + 47 @ args = 0, pretend = 0, frame = 0 + 48 @ frame_needed = 0, uses_anonymous_args = 0 + 49 @ link register save eliminated. + 50 .LVL1: + 92:stm32lib/src/stm32f10x_flash.c **** /* Check the parameters */ + 93:stm32lib/src/stm32f10x_flash.c **** assert_param(IS_FLASH_LATENCY(FLASH_Latency)); + 94:stm32lib/src/stm32f10x_flash.c **** + 95:stm32lib/src/stm32f10x_flash.c **** /* Sets the Latency value */ + 96:stm32lib/src/stm32f10x_flash.c **** FLASH->ACR &= ACR_LATENCY_Mask; + 51 .loc 1 96 0 + 52 0004 044A ldr r2, .L5 + 53 0006 1368 ldr r3, [r2, #0] + 54 0008 03F03803 and r3, r3, #56 + 55 000c 1360 str r3, [r2, #0] + 97:stm32lib/src/stm32f10x_flash.c **** FLASH->ACR |= FLASH_Latency; + 56 .loc 1 97 0 + 57 000e 1368 ldr r3, [r2, #0] + 58 0010 1843 orrs r0, r0, r3 + 59 .LVL2: + 60 0012 1060 str r0, [r2, #0] + 98:stm32lib/src/stm32f10x_flash.c **** } + 61 .loc 1 98 0 + 62 0014 7047 bx lr + 63 .L6: + 64 0016 00BF .align 2 + 65 .L5: + 66 0018 00200240 .word 1073881088 + 67 .LFE24: + 69 .align 2 + 70 .global FLASH_HalfCycleAccessCmd + 71 .thumb + 72 .thumb_func + 74 FLASH_HalfCycleAccessCmd: + 75 .LFB25: + 99:stm32lib/src/stm32f10x_flash.c **** + 100:stm32lib/src/stm32f10x_flash.c **** /******************************************************************************* + 101:stm32lib/src/stm32f10x_flash.c **** * Function Name : FLASH_HalfCycleAccessCmd + 102:stm32lib/src/stm32f10x_flash.c **** * Description : Enables or disables the Half cycle flash access. + 103:stm32lib/src/stm32f10x_flash.c **** * Input : - FLASH_HalfCycle: specifies the FLASH Half cycle Access mode. + 104:stm32lib/src/stm32f10x_flash.c **** * This parameter can be one of the following values: + 105:stm32lib/src/stm32f10x_flash.c **** * - FLASH_HalfCycleAccess_Enable: FLASH Half Cycle Enable + 106:stm32lib/src/stm32f10x_flash.c **** * - FLASH_HalfCycleAccess_Disable: FLASH Half Cycle Disable + 107:stm32lib/src/stm32f10x_flash.c **** * Output : None + 108:stm32lib/src/stm32f10x_flash.c **** * Return : None + 109:stm32lib/src/stm32f10x_flash.c **** *******************************************************************************/ + 110:stm32lib/src/stm32f10x_flash.c **** void FLASH_HalfCycleAccessCmd(u32 FLASH_HalfCycleAccess) + 111:stm32lib/src/stm32f10x_flash.c **** { + 76 .loc 1 111 0 + 77 @ args = 0, pretend = 0, frame = 0 + 78 @ frame_needed = 0, uses_anonymous_args = 0 + 79 @ link register save eliminated. + 80 .LVL3: + 112:stm32lib/src/stm32f10x_flash.c **** /* Check the parameters */ + 113:stm32lib/src/stm32f10x_flash.c **** assert_param(IS_FLASH_HALFCYCLEACCESS_STATE(FLASH_HalfCycleAccess)); + 114:stm32lib/src/stm32f10x_flash.c **** + 115:stm32lib/src/stm32f10x_flash.c **** /* Enable or disable the Half cycle access */ + 116:stm32lib/src/stm32f10x_flash.c **** FLASH->ACR &= ACR_HLFCYA_Mask; + 81 .loc 1 116 0 + 82 001c 044A ldr r2, .L9 + 83 001e 1368 ldr r3, [r2, #0] + 84 0020 23F00803 bic r3, r3, #8 + 85 0024 1360 str r3, [r2, #0] + 117:stm32lib/src/stm32f10x_flash.c **** FLASH->ACR |= FLASH_HalfCycleAccess; + 86 .loc 1 117 0 + 87 0026 1368 ldr r3, [r2, #0] + 88 0028 1843 orrs r0, r0, r3 + 89 .LVL4: + 90 002a 1060 str r0, [r2, #0] + 118:stm32lib/src/stm32f10x_flash.c **** } + 91 .loc 1 118 0 + 92 002c 7047 bx lr + 93 .L10: + 94 002e 00BF .align 2 + 95 .L9: + 96 0030 00200240 .word 1073881088 + 97 .LFE25: + 99 .align 2 + 100 .global FLASH_PrefetchBufferCmd + 101 .thumb + 102 .thumb_func + 104 FLASH_PrefetchBufferCmd: + 105 .LFB26: + 119:stm32lib/src/stm32f10x_flash.c **** + 120:stm32lib/src/stm32f10x_flash.c **** /******************************************************************************* + 121:stm32lib/src/stm32f10x_flash.c **** * Function Name : FLASH_PrefetchBufferCmd + 122:stm32lib/src/stm32f10x_flash.c **** * Description : Enables or disables the Prefetch Buffer. + 123:stm32lib/src/stm32f10x_flash.c **** * Input : - FLASH_PrefetchBuffer: specifies the Prefetch buffer status. + 124:stm32lib/src/stm32f10x_flash.c **** * This parameter can be one of the following values: + 125:stm32lib/src/stm32f10x_flash.c **** * - FLASH_PrefetchBuffer_Enable: FLASH Prefetch Buffer Enable + 126:stm32lib/src/stm32f10x_flash.c **** * - FLASH_PrefetchBuffer_Disable: FLASH Prefetch Buffer Disable + 127:stm32lib/src/stm32f10x_flash.c **** * Output : None + 128:stm32lib/src/stm32f10x_flash.c **** * Return : None + 129:stm32lib/src/stm32f10x_flash.c **** *******************************************************************************/ + 130:stm32lib/src/stm32f10x_flash.c **** + 131:stm32lib/src/stm32f10x_flash.c **** void FLASH_PrefetchBufferCmd(u32 FLASH_PrefetchBuffer) + 132:stm32lib/src/stm32f10x_flash.c **** { + 106 .loc 1 132 0 + 107 @ args = 0, pretend = 0, frame = 0 + 108 @ frame_needed = 0, uses_anonymous_args = 0 + 109 @ link register save eliminated. + 110 .LVL5: + 133:stm32lib/src/stm32f10x_flash.c **** /* Check the parameters */ + 134:stm32lib/src/stm32f10x_flash.c **** assert_param(IS_FLASH_PREFETCHBUFFER_STATE(FLASH_PrefetchBuffer)); + 135:stm32lib/src/stm32f10x_flash.c **** + 136:stm32lib/src/stm32f10x_flash.c **** /* Enable or disable the Prefetch Buffer */ + 137:stm32lib/src/stm32f10x_flash.c **** FLASH->ACR &= ACR_PRFTBE_Mask; + 111 .loc 1 137 0 + 112 0034 044A ldr r2, .L13 + 113 0036 1368 ldr r3, [r2, #0] + 114 0038 23F01003 bic r3, r3, #16 + 115 003c 1360 str r3, [r2, #0] + 138:stm32lib/src/stm32f10x_flash.c **** FLASH->ACR |= FLASH_PrefetchBuffer; + 116 .loc 1 138 0 + 117 003e 1368 ldr r3, [r2, #0] + 118 0040 1843 orrs r0, r0, r3 + 119 .LVL6: + 120 0042 1060 str r0, [r2, #0] + 139:stm32lib/src/stm32f10x_flash.c **** } + 121 .loc 1 139 0 + 122 0044 7047 bx lr + 123 .L14: + 124 0046 00BF .align 2 + 125 .L13: + 126 0048 00200240 .word 1073881088 + 127 .LFE26: + 177 .Letext0: +DEFINED SYMBOLS + *ABS*:00000000 stm32f10x_flash.c + /tmp/cc4fVZLL.s:22 .text:00000000 $t + /tmp/cc4fVZLL.s:27 .text:00000000 test + /tmp/cc4fVZLL.s:44 .text:00000004 FLASH_SetLatency + /tmp/cc4fVZLL.s:66 .text:00000018 $d + /tmp/cc4fVZLL.s:69 .text:0000001c $t + /tmp/cc4fVZLL.s:74 .text:0000001c FLASH_HalfCycleAccessCmd + /tmp/cc4fVZLL.s:96 .text:00000030 $d + /tmp/cc4fVZLL.s:99 .text:00000034 $t + /tmp/cc4fVZLL.s:104 .text:00000034 FLASH_PrefetchBufferCmd + /tmp/cc4fVZLL.s:126 .text:00000048 $d + +NO UNDEFINED SYMBOLS diff --git a/src/stm32lib/src/stm32f10x_fsmc.c b/src/stm32lib/src/stm32f10x_fsmc.c new file mode 100644 index 0000000..4068a7f --- /dev/null +++ b/src/stm32lib/src/stm32f10x_fsmc.c @@ -0,0 +1,861 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_fsmc.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the FSMC firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_fsmc.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* --------------------- FSMC registers bit mask ---------------------------- */
+/* FSMC BCRx Mask */
+#define BCR_MBKEN_Set ((u32)0x00000001)
+#define BCR_MBKEN_Reset ((u32)0x000FFFFE)
+#define BCR_FACCEN_Set ((u32)0x00000040)
+
+/* FSMC PCRx Mask */
+#define PCR_PBKEN_Set ((u32)0x00000004)
+#define PCR_PBKEN_Reset ((u32)0x000FFFFB)
+#define PCR_ECCEN_Set ((u32)0x00000040)
+#define PCR_ECCEN_Reset ((u32)0x000FFFBF)
+#define PCR_MemoryType_NAND ((u32)0x00000008)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : FSMC_NORSRAMDeInit
+* Description : Deinitializes the FSMC NOR/SRAM Banks registers to their default
+* reset values.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1
+* - FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2
+* - FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3
+* - FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NORSRAMDeInit(u32 FSMC_Bank)
+{
+ /* Check the parameter */
+ assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank));
+
+ /* FSMC_Bank1_NORSRAM1 */
+ if(FSMC_Bank == FSMC_Bank1_NORSRAM1)
+ {
+ FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030DB;
+ }
+ /* FSMC_Bank1_NORSRAM2, FSMC_Bank1_NORSRAM3 or FSMC_Bank1_NORSRAM4 */
+ else
+ {
+ FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030D2;
+ }
+
+ FSMC_Bank1->BTCR[FSMC_Bank + 1] = 0x0FFFFFFF;
+ FSMC_Bank1E->BWTR[FSMC_Bank] = 0x0FFFFFFF;
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NANDDeInit
+* Description : Deinitializes the FSMC NAND Banks registers to their default
+* reset values.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NANDDeInit(u32 FSMC_Bank)
+{
+ /* Check the parameter */
+ assert_param(IS_FSMC_NAND_BANK(FSMC_Bank));
+
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ /* Set the FSMC_Bank2 registers to their reset values */
+ FSMC_Bank2->PCR2 = 0x00000018;
+ FSMC_Bank2->SR2 = 0x00000040;
+ FSMC_Bank2->PMEM2 = 0xFCFCFCFC;
+ FSMC_Bank2->PATT2 = 0xFCFCFCFC;
+ }
+ /* FSMC_Bank3_NAND */
+ else
+ {
+ /* Set the FSMC_Bank3 registers to their reset values */
+ FSMC_Bank3->PCR3 = 0x00000018;
+ FSMC_Bank3->SR3 = 0x00000040;
+ FSMC_Bank3->PMEM3 = 0xFCFCFCFC;
+ FSMC_Bank3->PATT3 = 0xFCFCFCFC;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_PCCARDDeInit
+* Description : Deinitializes the FSMC PCCARD Bank registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_PCCARDDeInit(void)
+{
+ /* Set the FSMC_Bank4 registers to their reset values */
+ FSMC_Bank4->PCR4 = 0x00000018;
+ FSMC_Bank4->SR4 = 0x00000000;
+ FSMC_Bank4->PMEM4 = 0xFCFCFCFC;
+ FSMC_Bank4->PATT4 = 0xFCFCFCFC;
+ FSMC_Bank4->PIO4 = 0xFCFCFCFC;
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NORSRAMInit
+* Description : Initializes the FSMC NOR/SRAM Banks according to the
+* specified parameters in the FSMC_NORSRAMInitStruct.
+* Input : - FSMC_NORSRAMInitStruct : pointer to a FSMC_NORSRAMInitTypeDef
+* structure that contains the configuration information for
+* the FSMC NOR/SRAM specified Banks.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_FSMC_NORSRAM_BANK(FSMC_NORSRAMInitStruct->FSMC_Bank));
+ assert_param(IS_FSMC_MUX(FSMC_NORSRAMInitStruct->FSMC_DataAddressMux));
+ assert_param(IS_FSMC_MEMORY(FSMC_NORSRAMInitStruct->FSMC_MemoryType));
+ assert_param(IS_FSMC_MEMORY_WIDTH(FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth));
+ assert_param(IS_FSMC_BURSTMODE(FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode));
+ assert_param(IS_FSMC_WAIT_POLARITY(FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity));
+ assert_param(IS_FSMC_WRAP_MODE(FSMC_NORSRAMInitStruct->FSMC_WrapMode));
+ assert_param(IS_FSMC_WAIT_SIGNAL_ACTIVE(FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive));
+ assert_param(IS_FSMC_WRITE_OPERATION(FSMC_NORSRAMInitStruct->FSMC_WriteOperation));
+ assert_param(IS_FSMC_WAITE_SIGNAL(FSMC_NORSRAMInitStruct->FSMC_WaitSignal));
+ assert_param(IS_FSMC_EXTENDED_MODE(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode));
+ assert_param(IS_FSMC_ASYNC_WAIT(FSMC_NORSRAMInitStruct->FSMC_AsyncWait));
+ assert_param(IS_FSMC_WRITE_BURST(FSMC_NORSRAMInitStruct->FSMC_WriteBurst));
+ assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime));
+ assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime));
+ assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime));
+ assert_param(IS_FSMC_TURNAROUND_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration));
+ assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision));
+ assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency));
+ assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode));
+
+ /* Bank1 NOR/SRAM control register configuration */
+ FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] =
+ (u32)FSMC_NORSRAMInitStruct->FSMC_DataAddressMux |
+ FSMC_NORSRAMInitStruct->FSMC_MemoryType |
+ FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth |
+ FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode |
+ FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity |
+ FSMC_NORSRAMInitStruct->FSMC_WrapMode |
+ FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive |
+ FSMC_NORSRAMInitStruct->FSMC_WriteOperation |
+ FSMC_NORSRAMInitStruct->FSMC_WaitSignal |
+ FSMC_NORSRAMInitStruct->FSMC_ExtendedMode |
+ FSMC_NORSRAMInitStruct->FSMC_AsyncWait |
+ FSMC_NORSRAMInitStruct->FSMC_WriteBurst;
+
+ if(FSMC_NORSRAMInitStruct->FSMC_MemoryType == FSMC_MemoryType_NOR)
+ {
+ FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] |= (u32)BCR_FACCEN_Set;
+ }
+
+ /* Bank1 NOR/SRAM timing register configuration */
+ FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank+1] =
+ (u32)FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime |
+ (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime << 4) |
+ (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime << 8) |
+ (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration << 16) |
+ (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision << 20) |
+ (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency << 24) |
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode;
+
+
+
+ /* Bank1 NOR/SRAM timing register for write configuration, if extended mode is used */
+ if(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode == FSMC_ExtendedMode_Enable)
+ {
+ assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime));
+ assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime));
+ assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime));
+ assert_param(IS_FSMC_TURNAROUND_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_BusTurnAroundDuration));
+ assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision));
+ assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency));
+ assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode));
+
+ FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] =
+ (u32)FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime |
+ (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime << 4 )|
+ (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime << 8) |
+ (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_BusTurnAroundDuration << 16) |
+ (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision << 20) |
+ (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency << 24) |
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode;
+ }
+ else
+ {
+ FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = 0x0FFFFFFF;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NANDInit
+* Description : Initializes the FSMC NAND Banks according to the specified
+* parameters in the FSMC_NANDInitStruct.
+* Input : - FSMC_NANDInitStruct : pointer to a FSMC_NANDInitTypeDef
+* structure that contains the configuration information for
+* the FSMC NAND specified Banks.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct)
+{
+ u32 tmppcr = 0x00000000, tmppmem = 0x00000000, tmppatt = 0x00000000;
+
+ /* Check the parameters */
+ assert_param( IS_FSMC_NAND_BANK(FSMC_NANDInitStruct->FSMC_Bank));
+ assert_param( IS_FSMC_WAIT_FEATURE(FSMC_NANDInitStruct->FSMC_Waitfeature));
+ assert_param( IS_FSMC_DATA_WIDTH(FSMC_NANDInitStruct->FSMC_MemoryDataWidth));
+ assert_param( IS_FSMC_ECC_STATE(FSMC_NANDInitStruct->FSMC_ECC));
+ assert_param( IS_FSMC_ECCPAGE_SIZE(FSMC_NANDInitStruct->FSMC_ECCPageSize));
+ assert_param( IS_FSMC_ADDRESS_LOW_MAPPING(FSMC_NANDInitStruct->FSMC_AddressLowMapping));
+ assert_param( IS_FSMC_TCLR_TIME(FSMC_NANDInitStruct->FSMC_TCLRSetupTime));
+ assert_param( IS_FSMC_TAR_TIME(FSMC_NANDInitStruct->FSMC_TARSetupTime));
+
+ assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime));
+ assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime));
+ assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime));
+ assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime));
+
+ assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime));
+ assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime));
+ assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime));
+ assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime));
+
+ /* Set the tmppcr value according to FSMC_NANDInitStruct parameters */
+ tmppcr = (u32)FSMC_NANDInitStruct->FSMC_Waitfeature |
+ PCR_MemoryType_NAND |
+ FSMC_NANDInitStruct->FSMC_MemoryDataWidth |
+ FSMC_NANDInitStruct->FSMC_ECC |
+ FSMC_NANDInitStruct->FSMC_ECCPageSize |
+ FSMC_NANDInitStruct->FSMC_AddressLowMapping |
+ (FSMC_NANDInitStruct->FSMC_TCLRSetupTime << 9 )|
+ (FSMC_NANDInitStruct->FSMC_TARSetupTime << 13);
+
+ /* Set tmppmem value according to FSMC_CommonSpaceTimingStructure parameters */
+ tmppmem = (u32)FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime |
+ (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+ (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+ (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24);
+
+ /* Set tmppatt value according to FSMC_AttributeSpaceTimingStructure parameters */
+ tmppatt = (u32)FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime |
+ (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+ (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+ (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24);
+
+ if(FSMC_NANDInitStruct->FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ /* FSMC_Bank2_NAND registers configuration */
+ FSMC_Bank2->PCR2 = tmppcr;
+ FSMC_Bank2->PMEM2 = tmppmem;
+ FSMC_Bank2->PATT2 = tmppatt;
+ }
+ else
+ {
+ /* FSMC_Bank3_NAND registers configuration */
+ FSMC_Bank3->PCR3 = tmppcr;
+ FSMC_Bank3->PMEM3 = tmppmem;
+ FSMC_Bank3->PATT3 = tmppatt;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_PCCARDInit
+* Description : Initializes the FSMC PCCARD Bank according to the specified
+* parameters in the FSMC_PCCARDInitStruct.
+* Input : - FSMC_PCCARDInitStruct : pointer to a FSMC_PCCARDInitTypeDef
+* structure that contains the configuration information for
+* the FSMC PCCARD Bank.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_FSMC_WAIT_FEATURE(FSMC_PCCARDInitStruct->FSMC_Waitfeature));
+ assert_param(IS_FSMC_ADDRESS_LOW_MAPPING(FSMC_PCCARDInitStruct->FSMC_AddressLowMapping));
+ assert_param(IS_FSMC_TCLR_TIME(FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime));
+ assert_param(IS_FSMC_TAR_TIME(FSMC_PCCARDInitStruct->FSMC_TARSetupTime));
+
+
+ assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime));
+ assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime));
+ assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime));
+ assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime));
+
+ assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime));
+ assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime));
+ assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime));
+ assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime));
+
+ assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime));
+ assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime));
+ assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime));
+ assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime));
+
+ /* Set the PCR4 register value according to FSMC_PCCARDInitStruct parameters */
+ FSMC_Bank4->PCR4 = (u32)FSMC_PCCARDInitStruct->FSMC_Waitfeature |
+ FSMC_PCCARDInitStruct->FSMC_AddressLowMapping |
+ (FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime << 9) |
+ (FSMC_PCCARDInitStruct->FSMC_TARSetupTime << 13);
+
+ /* Set PMEM4 register value according to FSMC_CommonSpaceTimingStructure parameters */
+ FSMC_Bank4->PMEM4 = (u32)FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime |
+ (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+ (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+ (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24);
+
+ /* Set PATT4 register value according to FSMC_AttributeSpaceTimingStructure parameters */
+ FSMC_Bank4->PATT4 = (u32)FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime |
+ (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+ (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+ (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24);
+
+ /* Set PIO4 register value according to FSMC_IOSpaceTimingStructure parameters */
+ FSMC_Bank4->PIO4 = (u32)FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime |
+ (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+ (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+ (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime << 24);
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NORSRAMStructInit
+* Description : Fills each FSMC_NORSRAMInitStruct member with its default value.
+* Input : - FSMC_NORSRAMInitStruct: pointer to a FSMC_NORSRAMInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct)
+{
+ /* Reset NOR/SRAM Init structure parameters values */
+ FSMC_NORSRAMInitStruct->FSMC_Bank = FSMC_Bank1_NORSRAM1;
+ FSMC_NORSRAMInitStruct->FSMC_DataAddressMux = FSMC_DataAddressMux_Enable;
+ FSMC_NORSRAMInitStruct->FSMC_MemoryType = FSMC_MemoryType_SRAM;
+ FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b;
+ FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+ FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+ FSMC_NORSRAMInitStruct->FSMC_WrapMode = FSMC_WrapMode_Disable;
+ FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+ FSMC_NORSRAMInitStruct->FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+ FSMC_NORSRAMInitStruct->FSMC_WaitSignal = FSMC_WaitSignal_Enable;
+ FSMC_NORSRAMInitStruct->FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+ FSMC_NORSRAMInitStruct->FSMC_AsyncWait = FSMC_AsyncWait_Disable;
+ FSMC_NORSRAMInitStruct->FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime = 0xFF;
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A;
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime = 0xFF;
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency = 0xF;
+ FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A;
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NANDStructInit
+* Description : Fills each FSMC_NANDInitStruct member with its default value.
+* Input : - FSMC_NORSRAMInitStruct: pointer to a FSMC_NANDInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct)
+{
+ /* Reset NAND Init structure parameters values */
+ FSMC_NANDInitStruct->FSMC_Bank = FSMC_Bank2_NAND;
+ FSMC_NANDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable;
+ FSMC_NANDInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b;
+ FSMC_NANDInitStruct->FSMC_ECC = FSMC_ECC_Disable;
+ FSMC_NANDInitStruct->FSMC_ECCPageSize = FSMC_ECCPageSize_256Bytes;
+ FSMC_NANDInitStruct->FSMC_AddressLowMapping = FSMC_AddressLowMapping_Direct;
+ FSMC_NANDInitStruct->FSMC_TCLRSetupTime = 0x0;
+ FSMC_NANDInitStruct->FSMC_TARSetupTime = 0x0;
+ FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+ FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+ FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+ FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+ FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+ FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+ FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+ FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+}
+
+/*******************************************************************************
+* Function Name : FSMC_PCCARDStructInit
+* Description : Fills each FSMC_PCCARDInitStruct member with its default value.
+* Input : - FSMC_PCCARDInitStruct: pointer to a FSMC_PCCARDInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct)
+{
+ /* Reset PCCARD Init structure parameters values */
+ FSMC_PCCARDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable;
+ FSMC_PCCARDInitStruct->FSMC_AddressLowMapping = FSMC_AddressLowMapping_Direct;
+ FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime = 0x0;
+ FSMC_PCCARDInitStruct->FSMC_TARSetupTime = 0x0;
+ FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+ FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NORSRAMCmd
+* Description : Enables or disables the specified NOR/SRAM Memory Bank.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1
+* - FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2
+* - FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3
+* - FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4
+* : - NewState: new state of the FSMC_Bank.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NORSRAMCmd(u32 FSMC_Bank, FunctionalState NewState)
+{
+ assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected NOR/SRAM Bank by setting the PBKEN bit in the BCRx register */
+ FSMC_Bank1->BTCR[FSMC_Bank] |= BCR_MBKEN_Set;
+ }
+ else
+ {
+ /* Disable the selected NOR/SRAM Bank by clearing the PBKEN bit in the BCRx register */
+ FSMC_Bank1->BTCR[FSMC_Bank] &= BCR_MBKEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NANDCmd
+* Description : Enables or disables the specified NAND Memory Bank.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* : - NewState: new state of the FSMC_Bank.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NANDCmd(u32 FSMC_Bank, FunctionalState NewState)
+{
+ assert_param(IS_FSMC_NAND_BANK(FSMC_Bank));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected NAND Bank by setting the PBKEN bit in the PCRx register */
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ FSMC_Bank2->PCR2 |= PCR_PBKEN_Set;
+ }
+ else
+ {
+ FSMC_Bank3->PCR3 |= PCR_PBKEN_Set;
+ }
+ }
+ else
+ {
+ /* Disable the selected NAND Bank by clearing the PBKEN bit in the PCRx register */
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ FSMC_Bank2->PCR2 &= PCR_PBKEN_Reset;
+ }
+ else
+ {
+ FSMC_Bank3->PCR3 &= PCR_PBKEN_Reset;
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_PCCARDCmd
+* Description : Enables or disables the PCCARD Memory Bank.
+* Input : - NewState: new state of the PCCARD Memory Bank.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_PCCARDCmd(FunctionalState NewState)
+{
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the PCCARD Bank by setting the PBKEN bit in the PCR4 register */
+ FSMC_Bank4->PCR4 |= PCR_PBKEN_Set;
+ }
+ else
+ {
+ /* Disable the PCCARD Bank by clearing the PBKEN bit in the PCR4 register */
+ FSMC_Bank4->PCR4 &= PCR_PBKEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_NANDECCCmd
+* Description : Enables or disables the FSMC NAND ECC feature.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* : - NewState: new state of the FSMC NAND ECC feature.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_NANDECCCmd(u32 FSMC_Bank, FunctionalState NewState)
+{
+ assert_param(IS_FSMC_NAND_BANK(FSMC_Bank));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected NAND Bank ECC function by setting the ECCEN bit in the PCRx register */
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ FSMC_Bank2->PCR2 |= PCR_ECCEN_Set;
+ }
+ else
+ {
+ FSMC_Bank3->PCR3 |= PCR_ECCEN_Set;
+ }
+ }
+ else
+ {
+ /* Disable the selected NAND Bank ECC function by clearing the ECCEN bit in the PCRx register */
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ FSMC_Bank2->PCR2 &= PCR_ECCEN_Reset;
+ }
+ else
+ {
+ FSMC_Bank3->PCR3 &= PCR_ECCEN_Reset;
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_GetECC
+* Description : Returns the error correction code register value.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* Output : None
+* Return : The Error Correction Code (ECC) value.
+*******************************************************************************/
+u32 FSMC_GetECC(u32 FSMC_Bank)
+{
+ u32 eccval = 0x00000000;
+
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ /* Get the ECCR2 register value */
+ eccval = FSMC_Bank2->ECCR2;
+ }
+ else
+ {
+ /* Get the ECCR3 register value */
+ eccval = FSMC_Bank3->ECCR3;
+ }
+ /* Return the error correction code value */
+ return(eccval);
+}
+
+/*******************************************************************************
+* Function Name : FSMC_ITConfig
+* Description : Enables or disables the specified FSMC interrupts.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* - FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+* - FSMC_IT: specifies the FSMC interrupt sources to be
+* enabled or disabled.
+* This parameter can be any combination of the following values:
+* - FSMC_IT_RisingEdge: Rising edge detection interrupt.
+* - FSMC_IT_Level: Level edge detection interrupt.
+* - FSMC_IT_FallingEdge: Falling edge detection interrupt.
+* - NewState: new state of the specified FSMC interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_ITConfig(u32 FSMC_Bank, u32 FSMC_IT, FunctionalState NewState)
+{
+ assert_param(IS_FSMC_IT_BANK(FSMC_Bank));
+ assert_param(IS_FSMC_IT(FSMC_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected FSMC_Bank2 interrupts */
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ FSMC_Bank2->SR2 |= FSMC_IT;
+ }
+ /* Enable the selected FSMC_Bank3 interrupts */
+ else if (FSMC_Bank == FSMC_Bank3_NAND)
+ {
+ FSMC_Bank3->SR3 |= FSMC_IT;
+ }
+ /* Enable the selected FSMC_Bank4 interrupts */
+ else
+ {
+ FSMC_Bank4->SR4 |= FSMC_IT;
+ }
+ }
+ else
+ {
+ /* Disable the selected FSMC_Bank2 interrupts */
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+
+ FSMC_Bank2->SR2 &= (u32)~FSMC_IT;
+ }
+ /* Disable the selected FSMC_Bank3 interrupts */
+ else if (FSMC_Bank == FSMC_Bank3_NAND)
+ {
+ FSMC_Bank3->SR3 &= (u32)~FSMC_IT;
+ }
+ /* Disable the selected FSMC_Bank4 interrupts */
+ else
+ {
+ FSMC_Bank4->SR4 &= (u32)~FSMC_IT;
+ }
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_GetFlagStatus
+* Description : Checks whether the specified FSMC flag is set or not.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* - FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+* - FSMC_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - FSMC_FLAG_RisingEdge: Rising egde detection Flag.
+* - FSMC_FLAG_Level: Level detection Flag.
+* - FSMC_FLAG_FallingEdge: Falling egde detection Flag.
+* - FSMC_FLAG_FEMPT: Fifo empty Flag.
+* Output : None
+* Return : The new state of FSMC_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus FSMC_GetFlagStatus(u32 FSMC_Bank, u32 FSMC_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+ u32 tmpsr = 0x00000000;
+
+ /* Check the parameters */
+ assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank));
+ assert_param(IS_FSMC_GET_FLAG(FSMC_FLAG));
+
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ tmpsr = FSMC_Bank2->SR2;
+ }
+ else if(FSMC_Bank == FSMC_Bank3_NAND)
+ {
+ tmpsr = FSMC_Bank3->SR3;
+ }
+ /* FSMC_Bank4_PCCARD*/
+ else
+ {
+ tmpsr = FSMC_Bank4->SR4;
+ }
+
+ /* Get the flag status */
+ if ((tmpsr & FSMC_FLAG) != (u16)RESET )
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ /* Return the flag status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : FSMC_ClearFlag
+* Description : Clears the FSMC’s pending flags.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* - FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+* - FSMC_FLAG: specifies the flag to clear.
+* This parameter can be any combination of the following values:
+* - FSMC_FLAG_RisingEdge: Rising egde detection Flag.
+* - FSMC_FLAG_Level: Level detection Flag.
+* - FSMC_FLAG_FallingEdge: Falling egde detection Flag.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_ClearFlag(u32 FSMC_Bank, u32 FSMC_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank));
+ assert_param(IS_FSMC_CLEAR_FLAG(FSMC_FLAG)) ;
+
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ FSMC_Bank2->SR2 &= ~FSMC_FLAG;
+ }
+ else if(FSMC_Bank == FSMC_Bank3_NAND)
+ {
+ FSMC_Bank3->SR3 &= ~FSMC_FLAG;
+ }
+ /* FSMC_Bank4_PCCARD*/
+ else
+ {
+ FSMC_Bank4->SR4 &= ~FSMC_FLAG;
+ }
+}
+
+/*******************************************************************************
+* Function Name : FSMC_GetITStatus
+* Description : Checks whether the specified FSMC interrupt has occurred or not.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* - FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+* - FSMC_IT: specifies the FSMC interrupt source to check.
+* This parameter can be one of the following values:
+* - FSMC_IT_RisingEdge: Rising edge detection interrupt.
+* - FSMC_IT_Level: Level edge detection interrupt.
+* - FSMC_IT_FallingEdge: Falling edge detection interrupt.
+* Output : None
+* Return : The new state of FSMC_IT (SET or RESET).
+*******************************************************************************/
+ITStatus FSMC_GetITStatus(u32 FSMC_Bank, u32 FSMC_IT)
+{
+ ITStatus bitstatus = RESET;
+ u32 tmpsr = 0x0, itstatus = 0x0, itenable = 0x0;
+
+ /* Check the parameters */
+ assert_param(IS_FSMC_IT_BANK(FSMC_Bank));
+ assert_param(IS_FSMC_GET_IT(FSMC_IT));
+
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ tmpsr = FSMC_Bank2->SR2;
+ }
+ else if(FSMC_Bank == FSMC_Bank3_NAND)
+ {
+ tmpsr = FSMC_Bank3->SR3;
+ }
+ /* FSMC_Bank4_PCCARD*/
+ else
+ {
+ tmpsr = FSMC_Bank4->SR4;
+ }
+
+ itstatus = tmpsr & FSMC_IT;
+
+ itenable = tmpsr & (FSMC_IT >> 3);
+
+ if ((itstatus != (u32)RESET) && (itenable != (u32)RESET))
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : FSMC_ClearITPendingBit
+* Description : Clears the FSMC’s interrupt pending bits.
+* Input : - FSMC_Bank: specifies the FSMC Bank to be used
+* This parameter can be one of the following values:
+* - FSMC_Bank2_NAND: FSMC Bank2 NAND
+* - FSMC_Bank3_NAND: FSMC Bank3 NAND
+* - FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+* - FSMC_IT: specifies the interrupt pending bit to clear.
+* This parameter can be any combination of the following values:
+* - FSMC_IT_RisingEdge: Rising edge detection interrupt.
+* - FSMC_IT_Level: Level edge detection interrupt.
+* - FSMC_IT_FallingEdge: Falling edge detection interrupt.
+* Output : None
+* Return : None
+*******************************************************************************/
+void FSMC_ClearITPendingBit(u32 FSMC_Bank, u32 FSMC_IT)
+{
+ /* Check the parameters */
+ assert_param(IS_FSMC_IT_BANK(FSMC_Bank));
+ assert_param(IS_FSMC_IT(FSMC_IT));
+
+ if(FSMC_Bank == FSMC_Bank2_NAND)
+ {
+ FSMC_Bank2->SR2 &= ~(FSMC_IT >> 3);
+ }
+ else if(FSMC_Bank == FSMC_Bank3_NAND)
+ {
+ FSMC_Bank3->SR3 &= ~(FSMC_IT >> 3);
+ }
+ /* FSMC_Bank4_PCCARD*/
+ else
+ {
+ FSMC_Bank4->SR4 &= ~(FSMC_IT >> 3);
+ }
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_gpio.c b/src/stm32lib/src/stm32f10x_gpio.c new file mode 100644 index 0000000..1979c05 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_gpio.c @@ -0,0 +1,583 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_gpio.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the GPIO firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_gpio.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ------------ RCC registers bit address in the alias region ----------- */
+#define AFIO_OFFSET (AFIO_BASE - PERIPH_BASE)
+
+/* --- EVENTCR Register ---*/
+/* Alias word address of EVOE bit */
+#define EVCR_OFFSET (AFIO_OFFSET + 0x00)
+#define EVOE_BitNumber ((u8)0x07)
+#define EVCR_EVOE_BB (PERIPH_BB_BASE + (EVCR_OFFSET * 32) + (EVOE_BitNumber * 4))
+
+#define EVCR_PORTPINCONFIG_MASK ((u16)0xFF80)
+#define LSB_MASK ((u16)0xFFFF)
+#define DBGAFR_POSITION_MASK ((u32)0x000F0000)
+#define DBGAFR_SWJCFG_MASK ((u32)0xF0FFFFFF)
+#define DBGAFR_LOCATION_MASK ((u32)0x00200000)
+#define DBGAFR_NUMBITS_MASK ((u32)0x00100000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : GPIO_DeInit
+* Description : Deinitializes the GPIOx peripheral registers to their default
+* reset values.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_DeInit(GPIO_TypeDef* GPIOx)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+
+ switch (*(u32*)&GPIOx)
+ {
+ case GPIOA_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, DISABLE);
+ break;
+
+ case GPIOB_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, DISABLE);
+ break;
+
+ case GPIOC_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, DISABLE);
+ break;
+
+ case GPIOD_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, DISABLE);
+ break;
+
+ case GPIOE_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, DISABLE);
+ break;
+
+ case GPIOF_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, DISABLE);
+ break;
+
+ case GPIOG_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, DISABLE);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : GPIO_AFIODeInit
+* Description : Deinitializes the Alternate Functions (remap, event control
+* and EXTI configuration) registers to their default reset
+* values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_AFIODeInit(void)
+{
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, DISABLE);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Init
+* Description : Initializes the GPIOx peripheral according to the specified
+* parameters in the GPIO_InitStruct.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* - GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure that
+* contains the configuration information for the specified GPIO
+* peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct)
+{
+ u32 currentmode = 0x00, currentpin = 0x00, pinpos = 0x00, pos = 0x00;
+ u32 tmpreg = 0x00, pinmask = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+ assert_param(IS_GPIO_MODE(GPIO_InitStruct->GPIO_Mode));
+ assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin));
+
+/*---------------------------- GPIO Mode Configuration -----------------------*/
+ currentmode = ((u32)GPIO_InitStruct->GPIO_Mode) & ((u32)0x0F);
+
+ if ((((u32)GPIO_InitStruct->GPIO_Mode) & ((u32)0x10)) != 0x00)
+ {
+ /* Check the parameters */
+ assert_param(IS_GPIO_SPEED(GPIO_InitStruct->GPIO_Speed));
+ /* Output mode */
+ currentmode |= (u32)GPIO_InitStruct->GPIO_Speed;
+ }
+
+/*---------------------------- GPIO CRL Configuration ------------------------*/
+ /* Configure the eight low port pins */
+ if (((u32)GPIO_InitStruct->GPIO_Pin & ((u32)0x00FF)) != 0x00)
+ {
+ tmpreg = GPIOx->CRL;
+
+ for (pinpos = 0x00; pinpos < 0x08; pinpos++)
+ {
+ pos = ((u32)0x01) << pinpos;
+ /* Get the port pins position */
+ currentpin = (GPIO_InitStruct->GPIO_Pin) & pos;
+
+ if (currentpin == pos)
+ {
+ pos = pinpos << 2;
+ /* Clear the corresponding low control register bits */
+ pinmask = ((u32)0x0F) << pos;
+ tmpreg &= ~pinmask;
+
+ /* Write the mode configuration in the corresponding bits */
+ tmpreg |= (currentmode << pos);
+
+ /* Reset the corresponding ODR bit */
+ if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD)
+ {
+ GPIOx->BRR = (((u32)0x01) << pinpos);
+ }
+ else
+ {
+ /* Set the corresponding ODR bit */
+ if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU)
+ {
+ GPIOx->BSRR = (((u32)0x01) << pinpos);
+ }
+ }
+ }
+ }
+ GPIOx->CRL = tmpreg;
+ }
+
+/*---------------------------- GPIO CRH Configuration ------------------------*/
+ /* Configure the eight high port pins */
+ if (GPIO_InitStruct->GPIO_Pin > 0x00FF)
+ {
+ tmpreg = GPIOx->CRH;
+ for (pinpos = 0x00; pinpos < 0x08; pinpos++)
+ {
+ pos = (((u32)0x01) << (pinpos + 0x08));
+ /* Get the port pins position */
+ currentpin = ((GPIO_InitStruct->GPIO_Pin) & pos);
+ if (currentpin == pos)
+ {
+ pos = pinpos << 2;
+ /* Clear the corresponding high control register bits */
+ pinmask = ((u32)0x0F) << pos;
+ tmpreg &= ~pinmask;
+
+ /* Write the mode configuration in the corresponding bits */
+ tmpreg |= (currentmode << pos);
+
+ /* Reset the corresponding ODR bit */
+ if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD)
+ {
+ GPIOx->BRR = (((u32)0x01) << (pinpos + 0x08));
+ }
+ /* Set the corresponding ODR bit */
+ if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU)
+ {
+ GPIOx->BSRR = (((u32)0x01) << (pinpos + 0x08));
+ }
+ }
+ }
+ GPIOx->CRH = tmpreg;
+ }
+}
+
+/*******************************************************************************
+* Function Name : GPIO_StructInit
+* Description : Fills each GPIO_InitStruct member with its default value.
+* Input : - GPIO_InitStruct : pointer to a GPIO_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct)
+{
+ /* Reset GPIO init structure parameters values */
+ GPIO_InitStruct->GPIO_Pin = GPIO_Pin_All;
+ GPIO_InitStruct->GPIO_Speed = GPIO_Speed_2MHz;
+ GPIO_InitStruct->GPIO_Mode = GPIO_Mode_IN_FLOATING;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_ReadInputDataBit
+* Description : Reads the specified input port pin.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* : - GPIO_Pin: specifies the port bit to read.
+* This parameter can be GPIO_Pin_x where x can be (0..15).
+* Output : None
+* Return : The input port pin value.
+*******************************************************************************/
+u8 GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin)
+{
+ u8 bitstatus = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+ assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
+
+ if ((GPIOx->IDR & GPIO_Pin) != (u32)Bit_RESET)
+ {
+ bitstatus = (u8)Bit_SET;
+ }
+ else
+ {
+ bitstatus = (u8)Bit_RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_ReadInputData
+* Description : Reads the specified GPIO input data port.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* Output : None
+* Return : GPIO input data port value.
+*******************************************************************************/
+u16 GPIO_ReadInputData(GPIO_TypeDef* GPIOx)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+
+ return ((u16)GPIOx->IDR);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_ReadOutputDataBit
+* Description : Reads the specified output data port bit.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* : - GPIO_Pin: specifies the port bit to read.
+* This parameter can be GPIO_Pin_x where x can be (0..15).
+* Output : None
+* Return : The output port pin value.
+*******************************************************************************/
+u8 GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin)
+{
+ u8 bitstatus = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+ assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
+
+ if ((GPIOx->ODR & GPIO_Pin) != (u32)Bit_RESET)
+ {
+ bitstatus = (u8)Bit_SET;
+ }
+ else
+ {
+ bitstatus = (u8)Bit_RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_ReadOutputData
+* Description : Reads the specified GPIO output data port.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* Output : None
+* Return : GPIO output data port value.
+*******************************************************************************/
+u16 GPIO_ReadOutputData(GPIO_TypeDef* GPIOx)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+
+ return ((u16)GPIOx->ODR);
+}
+
+/*******************************************************************************
+* Function Name : GPIO_SetBits
+* Description : Sets the selected data port bits.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* - GPIO_Pin: specifies the port bits to be written.
+* This parameter can be any combination of GPIO_Pin_x where
+* x can be (0..15).
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_SetBits(GPIO_TypeDef* GPIOx, u16 GPIO_Pin)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+ assert_param(IS_GPIO_PIN(GPIO_Pin));
+
+ GPIOx->BSRR = GPIO_Pin;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_ResetBits
+* Description : Clears the selected data port bits.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* - GPIO_Pin: specifies the port bits to be written.
+* This parameter can be any combination of GPIO_Pin_x where
+* x can be (0..15).
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_ResetBits(GPIO_TypeDef* GPIOx, u16 GPIO_Pin)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+ assert_param(IS_GPIO_PIN(GPIO_Pin));
+
+ GPIOx->BRR = GPIO_Pin;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_WriteBit
+* Description : Sets or clears the selected data port bit.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* - GPIO_Pin: specifies the port bit to be written.
+* This parameter can be one of GPIO_Pin_x where x can be (0..15).
+* - BitVal: specifies the value to be written to the selected bit.
+* This parameter can be one of the BitAction enum values:
+* - Bit_RESET: to clear the port pin
+* - Bit_SET: to set the port pin
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_WriteBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin, BitAction BitVal)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+ assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
+ assert_param(IS_GPIO_BIT_ACTION(BitVal));
+
+ if (BitVal != Bit_RESET)
+ {
+ GPIOx->BSRR = GPIO_Pin;
+ }
+ else
+ {
+ GPIOx->BRR = GPIO_Pin;
+ }
+}
+
+/*******************************************************************************
+* Function Name : GPIO_Write
+* Description : Writes data to the specified GPIO data port.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* - PortVal: specifies the value to be written to the port output
+* data register.
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_Write(GPIO_TypeDef* GPIOx, u16 PortVal)
+{
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+
+ GPIOx->ODR = PortVal;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_PinLockConfig
+* Description : Locks GPIO Pins configuration registers.
+* Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral.
+* - GPIO_Pin: specifies the port bit to be written.
+* This parameter can be any combination of GPIO_Pin_x where
+* x can be (0..15).
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, u16 GPIO_Pin)
+{
+ u32 tmp = 0x00010000;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+ assert_param(IS_GPIO_PIN(GPIO_Pin));
+
+ tmp |= GPIO_Pin;
+ /* Set LCKK bit */
+ GPIOx->LCKR = tmp;
+ /* Reset LCKK bit */
+ GPIOx->LCKR = GPIO_Pin;
+ /* Set LCKK bit */
+ GPIOx->LCKR = tmp;
+ /* Read LCKK bit*/
+ tmp = GPIOx->LCKR;
+ /* Read LCKK bit*/
+ tmp = GPIOx->LCKR;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_EventOutputConfig
+* Description : Selects the GPIO pin used as Event output.
+* Input : - GPIO_PortSource: selects the GPIO port to be used as source
+* for Event output.
+* This parameter can be GPIO_PortSourceGPIOx where x can be
+* (A..E).
+* - GPIO_PinSource: specifies the pin for the Event output.
+* This parameter can be GPIO_PinSourcex where x can be (0..15).
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_EventOutputConfig(u8 GPIO_PortSource, u8 GPIO_PinSource)
+{
+ u32 tmpreg = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_EVENTOUT_PORT_SOURCE(GPIO_PortSource));
+ assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource));
+
+ tmpreg = AFIO->EVCR;
+ /* Clear the PORT[6:4] and PIN[3:0] bits */
+ tmpreg &= EVCR_PORTPINCONFIG_MASK;
+ tmpreg |= (u32)GPIO_PortSource << 0x04;
+ tmpreg |= GPIO_PinSource;
+
+ AFIO->EVCR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_EventOutputCmd
+* Description : Enables or disables the Event Output.
+* Input : - NewState: new state of the Event output.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_EventOutputCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) EVCR_EVOE_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_PinRemapConfig
+* Description : Changes the mapping of the specified pin.
+* Input : - GPIO_Remap: selects the pin to remap.
+* This parameter can be one of the following values:
+* - GPIO_Remap_SPI1
+* - GPIO_Remap_I2C1
+* - GPIO_Remap_USART1
+* - GPIO_Remap_USART2
+* - GPIO_PartialRemap_USART3
+* - GPIO_FullRemap_USART3
+* - GPIO_PartialRemap_TIM1
+* - GPIO_FullRemap_TIM1
+* - GPIO_PartialRemap1_TIM2
+* - GPIO_PartialRemap2_TIM2
+* - GPIO_FullRemap_TIM2
+* - GPIO_PartialRemap_TIM3
+* - GPIO_FullRemap_TIM3
+* - GPIO_Remap_TIM4
+* - GPIO_Remap1_CAN
+* - GPIO_Remap2_CAN
+* - GPIO_Remap_PD01
+* - GPIO_Remap_TIM5CH4_LSI
+* - GPIO_Remap_ADC1_ETRGINJ
+* - GPIO_Remap_ADC1_ETRGREG
+* - GPIO_Remap_ADC2_ETRGINJ
+* - GPIO_Remap_ADC2_ETRGREG
+* - GPIO_Remap_SWJ_NoJTRST
+* - GPIO_Remap_SWJ_JTAGDisable
+* - GPIO_Remap_SWJ_Disable
+* - NewState: new state of the port pin remapping.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_PinRemapConfig(u32 GPIO_Remap, FunctionalState NewState)
+{
+ u32 tmp = 0x00, tmp1 = 0x00, tmpreg = 0x00, tmpmask = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_REMAP(GPIO_Remap));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ tmpreg = AFIO->MAPR;
+
+ tmpmask = (GPIO_Remap & DBGAFR_POSITION_MASK) >> 0x10;
+ tmp = GPIO_Remap & LSB_MASK;
+
+ if ((GPIO_Remap & (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) == (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK))
+ {
+ tmpreg &= DBGAFR_SWJCFG_MASK;
+ AFIO->MAPR &= DBGAFR_SWJCFG_MASK;
+ }
+ else if ((GPIO_Remap & DBGAFR_NUMBITS_MASK) == DBGAFR_NUMBITS_MASK)
+ {
+ tmp1 = ((u32)0x03) << tmpmask;
+ tmpreg &= ~tmp1;
+ tmpreg |= ~DBGAFR_SWJCFG_MASK;
+ }
+ else
+ {
+ tmpreg &= ~(tmp << ((GPIO_Remap >> 0x15)*0x10));
+ tmpreg |= ~DBGAFR_SWJCFG_MASK;
+ }
+
+ if (NewState != DISABLE)
+ {
+ tmpreg |= (tmp << ((GPIO_Remap >> 0x15)*0x10));
+ }
+
+ AFIO->MAPR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : GPIO_EXTILineConfig
+* Description : Selects the GPIO pin used as EXTI Line.
+* Input : - GPIO_PortSource: selects the GPIO port to be used as
+* source for EXTI lines.
+* This parameter can be GPIO_PortSourceGPIOx where x can be
+* (A..G).
+* - GPIO_PinSource: specifies the EXTI line to be configured.
+* This parameter can be GPIO_PinSourcex where x can be (0..15).
+* Output : None
+* Return : None
+*******************************************************************************/
+void GPIO_EXTILineConfig(u8 GPIO_PortSource, u8 GPIO_PinSource)
+{
+ u32 tmp = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GPIO_EXTI_PORT_SOURCE(GPIO_PortSource));
+ assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource));
+
+ tmp = ((u32)0x0F) << (0x04 * (GPIO_PinSource & (u8)0x03));
+
+ AFIO->EXTICR[GPIO_PinSource >> 0x02] &= ~tmp;
+ AFIO->EXTICR[GPIO_PinSource >> 0x02] |= (((u32)GPIO_PortSource) << (0x04 * (GPIO_PinSource & (u8)0x03)));
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_gpio.lst b/src/stm32lib/src/stm32f10x_gpio.lst new file mode 100644 index 0000000..a27618d --- /dev/null +++ b/src/stm32lib/src/stm32f10x_gpio.lst @@ -0,0 +1,1288 @@ + 1 .syntax unified + 2 .cpu cortex-m3 + 3 .fpu softvfp + 4 .eabi_attribute 20, 1 + 5 .eabi_attribute 21, 1 + 6 .eabi_attribute 23, 3 + 7 .eabi_attribute 24, 1 + 8 .eabi_attribute 25, 1 + 9 .eabi_attribute 26, 1 + 10 .eabi_attribute 30, 4 + 11 .eabi_attribute 18, 4 + 12 .thumb + 13 .file "stm32f10x_gpio.c" + 21 .Ltext0: + 22 .align 2 + 23 .global GPIO_Init + 24 .thumb + 25 .thumb_func + 27 GPIO_Init: + 28 .LFB25: + 29 .file 1 "stm32lib/src/stm32f10x_gpio.c" + 1:stm32lib/src/stm32f10x_gpio.c **** /******************** (C) COPYRIGHT 2008 STMicroelectronics ******************** + 2:stm32lib/src/stm32f10x_gpio.c **** * File Name : stm32f10x_gpio.c + 3:stm32lib/src/stm32f10x_gpio.c **** * Author : MCD Application Team + 4:stm32lib/src/stm32f10x_gpio.c **** * Version : V2.0.2 + 5:stm32lib/src/stm32f10x_gpio.c **** * Date : 07/11/2008 + 6:stm32lib/src/stm32f10x_gpio.c **** * Description : This file provides all the GPIO firmware functions. + 7:stm32lib/src/stm32f10x_gpio.c **** ******************************************************************************** + 8:stm32lib/src/stm32f10x_gpio.c **** * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + 9:stm32lib/src/stm32f10x_gpio.c **** * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. + 10:stm32lib/src/stm32f10x_gpio.c **** * AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, + 11:stm32lib/src/stm32f10x_gpio.c **** * INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE + 12:stm32lib/src/stm32f10x_gpio.c **** * CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING + 13:stm32lib/src/stm32f10x_gpio.c **** * INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + 14:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 15:stm32lib/src/stm32f10x_gpio.c **** + 16:stm32lib/src/stm32f10x_gpio.c **** /* Includes ------------------------------------------------------------------*/ + 17:stm32lib/src/stm32f10x_gpio.c **** #include "stm32f10x_gpio.h" + 18:stm32lib/src/stm32f10x_gpio.c **** #include "stm32f10x_rcc.h" + 19:stm32lib/src/stm32f10x_gpio.c **** + 20:stm32lib/src/stm32f10x_gpio.c **** /* Private typedef -----------------------------------------------------------*/ + 21:stm32lib/src/stm32f10x_gpio.c **** /* Private define ------------------------------------------------------------*/ + 22:stm32lib/src/stm32f10x_gpio.c **** /* ------------ RCC registers bit address in the alias region ----------- */ + 23:stm32lib/src/stm32f10x_gpio.c **** #define AFIO_OFFSET (AFIO_BASE - PERIPH_BASE) + 24:stm32lib/src/stm32f10x_gpio.c **** + 25:stm32lib/src/stm32f10x_gpio.c **** /* --- EVENTCR Register ---*/ + 26:stm32lib/src/stm32f10x_gpio.c **** /* Alias word address of EVOE bit */ + 27:stm32lib/src/stm32f10x_gpio.c **** #define EVCR_OFFSET (AFIO_OFFSET + 0x00) + 28:stm32lib/src/stm32f10x_gpio.c **** #define EVOE_BitNumber ((u8)0x07) + 29:stm32lib/src/stm32f10x_gpio.c **** #define EVCR_EVOE_BB (PERIPH_BB_BASE + (EVCR_OFFSET * 32) + (EVOE_BitNumber * 4)) + 30:stm32lib/src/stm32f10x_gpio.c **** + 31:stm32lib/src/stm32f10x_gpio.c **** #define EVCR_PORTPINCONFIG_MASK ((u16)0xFF80) + 32:stm32lib/src/stm32f10x_gpio.c **** #define LSB_MASK ((u16)0xFFFF) + 33:stm32lib/src/stm32f10x_gpio.c **** #define DBGAFR_POSITION_MASK ((u32)0x000F0000) + 34:stm32lib/src/stm32f10x_gpio.c **** #define DBGAFR_SWJCFG_MASK ((u32)0xF0FFFFFF) + 35:stm32lib/src/stm32f10x_gpio.c **** #define DBGAFR_LOCATION_MASK ((u32)0x00200000) + 36:stm32lib/src/stm32f10x_gpio.c **** #define DBGAFR_NUMBITS_MASK ((u32)0x00100000) + 37:stm32lib/src/stm32f10x_gpio.c **** + 38:stm32lib/src/stm32f10x_gpio.c **** /* Private macro -------------------------------------------------------------*/ + 39:stm32lib/src/stm32f10x_gpio.c **** /* Private variables ---------------------------------------------------------*/ + 40:stm32lib/src/stm32f10x_gpio.c **** /* Private function prototypes -----------------------------------------------*/ + 41:stm32lib/src/stm32f10x_gpio.c **** /* Private functions ---------------------------------------------------------*/ + 42:stm32lib/src/stm32f10x_gpio.c **** + 43:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 44:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_DeInit + 45:stm32lib/src/stm32f10x_gpio.c **** * Description : Deinitializes the GPIOx peripheral registers to their default + 46:stm32lib/src/stm32f10x_gpio.c **** * reset values. + 47:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral. + 48:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 49:stm32lib/src/stm32f10x_gpio.c **** * Return : None + 50:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 51:stm32lib/src/stm32f10x_gpio.c **** void GPIO_DeInit(GPIO_TypeDef* GPIOx) + 52:stm32lib/src/stm32f10x_gpio.c **** { + 53:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 54:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + 55:stm32lib/src/stm32f10x_gpio.c **** + 56:stm32lib/src/stm32f10x_gpio.c **** switch (*(u32*)&GPIOx) + 57:stm32lib/src/stm32f10x_gpio.c **** { + 58:stm32lib/src/stm32f10x_gpio.c **** case GPIOA_BASE: + 59:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, ENABLE); + 60:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, DISABLE); + 61:stm32lib/src/stm32f10x_gpio.c **** break; + 62:stm32lib/src/stm32f10x_gpio.c **** + 63:stm32lib/src/stm32f10x_gpio.c **** case GPIOB_BASE: + 64:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, ENABLE); + 65:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, DISABLE); + 66:stm32lib/src/stm32f10x_gpio.c **** break; + 67:stm32lib/src/stm32f10x_gpio.c **** + 68:stm32lib/src/stm32f10x_gpio.c **** case GPIOC_BASE: + 69:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, ENABLE); + 70:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, DISABLE); + 71:stm32lib/src/stm32f10x_gpio.c **** break; + 72:stm32lib/src/stm32f10x_gpio.c **** + 73:stm32lib/src/stm32f10x_gpio.c **** case GPIOD_BASE: + 74:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, ENABLE); + 75:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, DISABLE); + 76:stm32lib/src/stm32f10x_gpio.c **** break; + 77:stm32lib/src/stm32f10x_gpio.c **** + 78:stm32lib/src/stm32f10x_gpio.c **** case GPIOE_BASE: + 79:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, ENABLE); + 80:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, DISABLE); + 81:stm32lib/src/stm32f10x_gpio.c **** break; + 82:stm32lib/src/stm32f10x_gpio.c **** + 83:stm32lib/src/stm32f10x_gpio.c **** case GPIOF_BASE: + 84:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, ENABLE); + 85:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, DISABLE); + 86:stm32lib/src/stm32f10x_gpio.c **** break; + 87:stm32lib/src/stm32f10x_gpio.c **** + 88:stm32lib/src/stm32f10x_gpio.c **** case GPIOG_BASE: + 89:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, ENABLE); + 90:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, DISABLE); + 91:stm32lib/src/stm32f10x_gpio.c **** break; + 92:stm32lib/src/stm32f10x_gpio.c **** + 93:stm32lib/src/stm32f10x_gpio.c **** default: + 94:stm32lib/src/stm32f10x_gpio.c **** break; + 95:stm32lib/src/stm32f10x_gpio.c **** } + 96:stm32lib/src/stm32f10x_gpio.c **** } + 97:stm32lib/src/stm32f10x_gpio.c **** + 98:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 99:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_AFIODeInit + 100:stm32lib/src/stm32f10x_gpio.c **** * Description : Deinitializes the Alternate Functions (remap, event control + 101:stm32lib/src/stm32f10x_gpio.c **** * and EXTI configuration) registers to their default reset + 102:stm32lib/src/stm32f10x_gpio.c **** * values. + 103:stm32lib/src/stm32f10x_gpio.c **** * Input : None + 104:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 105:stm32lib/src/stm32f10x_gpio.c **** * Return : None + 106:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 107:stm32lib/src/stm32f10x_gpio.c **** void GPIO_AFIODeInit(void) + 108:stm32lib/src/stm32f10x_gpio.c **** { + 109:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, ENABLE); + 110:stm32lib/src/stm32f10x_gpio.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, DISABLE); + 111:stm32lib/src/stm32f10x_gpio.c **** } + 112:stm32lib/src/stm32f10x_gpio.c **** + 113:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 114:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_Init + 115:stm32lib/src/stm32f10x_gpio.c **** * Description : Initializes the GPIOx peripheral according to the specified + 116:stm32lib/src/stm32f10x_gpio.c **** * parameters in the GPIO_InitStruct. + 117:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral. + 118:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure that + 119:stm32lib/src/stm32f10x_gpio.c **** * contains the configuration information for the specified GPIO + 120:stm32lib/src/stm32f10x_gpio.c **** * peripheral. + 121:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 122:stm32lib/src/stm32f10x_gpio.c **** * Return : None + 123:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 124:stm32lib/src/stm32f10x_gpio.c **** void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct) + 125:stm32lib/src/stm32f10x_gpio.c **** { + 30 .loc 1 125 0 + 31 @ args = 0, pretend = 0, frame = 0 + 32 @ frame_needed = 0, uses_anonymous_args = 0 + 33 .LVL0: + 34 0000 F0B5 push {r4, r5, r6, r7, lr} + 35 .LCFI0: + 126:stm32lib/src/stm32f10x_gpio.c **** u32 currentmode = 0x00, currentpin = 0x00, pinpos = 0x00, pos = 0x00; + 127:stm32lib/src/stm32f10x_gpio.c **** u32 tmpreg = 0x00, pinmask = 0x00; + 128:stm32lib/src/stm32f10x_gpio.c **** + 129:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 130:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + 131:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_MODE(GPIO_InitStruct->GPIO_Mode)); + 132:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin)); + 133:stm32lib/src/stm32f10x_gpio.c **** + 134:stm32lib/src/stm32f10x_gpio.c **** /*---------------------------- GPIO Mode Configuration -----------------------*/ + 135:stm32lib/src/stm32f10x_gpio.c **** currentmode = ((u32)GPIO_InitStruct->GPIO_Mode) & ((u32)0x0F); + 36 .loc 1 135 0 + 37 0002 CD78 ldrb r5, [r1, #3] @ zero_extendqisi2 + 136:stm32lib/src/stm32f10x_gpio.c **** + 137:stm32lib/src/stm32f10x_gpio.c **** if ((((u32)GPIO_InitStruct->GPIO_Mode) & ((u32)0x10)) != 0x00) + 138:stm32lib/src/stm32f10x_gpio.c **** { + 139:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 140:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_SPEED(GPIO_InitStruct->GPIO_Speed)); + 141:stm32lib/src/stm32f10x_gpio.c **** /* Output mode */ + 142:stm32lib/src/stm32f10x_gpio.c **** currentmode |= (u32)GPIO_InitStruct->GPIO_Speed; + 143:stm32lib/src/stm32f10x_gpio.c **** } + 144:stm32lib/src/stm32f10x_gpio.c **** + 145:stm32lib/src/stm32f10x_gpio.c **** /*---------------------------- GPIO CRL Configuration ------------------------*/ + 146:stm32lib/src/stm32f10x_gpio.c **** /* Configure the eight low port pins */ + 147:stm32lib/src/stm32f10x_gpio.c **** if (((u32)GPIO_InitStruct->GPIO_Pin & ((u32)0x00FF)) != 0x00) + 38 .loc 1 147 0 + 39 0004 0E88 ldrh r6, [r1, #0] + 40 .loc 1 137 0 + 41 0006 15F0100F tst r5, #16 + 42 .loc 1 142 0 + 43 000a 18BF it ne + 44 000c 8B78 ldrbne r3, [r1, #2] @ zero_extendqisi2 + 45 .loc 1 135 0 + 46 000e 05F00F07 and r7, r5, #15 + 47 .LVL1: + 48 .loc 1 142 0 + 49 0012 18BF it ne + 50 0014 1F43 orrne r7, r7, r3 + 51 .loc 1 147 0 + 52 0016 16F0FF0F tst r6, #255 + 53 001a 20D0 beq .L3 + 148:stm32lib/src/stm32f10x_gpio.c **** { + 149:stm32lib/src/stm32f10x_gpio.c **** tmpreg = GPIOx->CRL; + 54 .loc 1 149 0 + 55 001c 0468 ldr r4, [r0, #0] + 56 .LVL2: + 57 001e 4FF0000C mov ip, #0 + 58 .LVL3: + 59 .L6: + 150:stm32lib/src/stm32f10x_gpio.c **** + 151:stm32lib/src/stm32f10x_gpio.c **** for (pinpos = 0x00; pinpos < 0x08; pinpos++) + 152:stm32lib/src/stm32f10x_gpio.c **** { + 153:stm32lib/src/stm32f10x_gpio.c **** pos = ((u32)0x01) << pinpos; + 60 .loc 1 153 0 + 61 0022 0123 movs r3, #1 + 62 .LVL4: + 63 0024 03FA0CF3 lsl r3, r3, ip + 64 .LVL5: + 154:stm32lib/src/stm32f10x_gpio.c **** /* Get the port pins position */ + 155:stm32lib/src/stm32f10x_gpio.c **** currentpin = (GPIO_InitStruct->GPIO_Pin) & pos; + 65 .loc 1 155 0 + 66 0028 03EA0601 and r1, r3, r6 + 67 .LVL6: + 156:stm32lib/src/stm32f10x_gpio.c **** + 157:stm32lib/src/stm32f10x_gpio.c **** if (currentpin == pos) + 68 .loc 1 157 0 + 69 002c 9942 cmp r1, r3 + 70 002e 10D1 bne .L4 + 158:stm32lib/src/stm32f10x_gpio.c **** { + 159:stm32lib/src/stm32f10x_gpio.c **** pos = pinpos << 2; + 160:stm32lib/src/stm32f10x_gpio.c **** /* Clear the corresponding low control register bits */ + 161:stm32lib/src/stm32f10x_gpio.c **** pinmask = ((u32)0x0F) << pos; + 71 .loc 1 161 0 + 72 0030 4FEA8C02 lsl r2, ip, #2 + 162:stm32lib/src/stm32f10x_gpio.c **** tmpreg &= ~pinmask; + 73 .loc 1 162 0 + 74 0034 0F23 movs r3, #15 + 75 .LVL7: + 76 0036 9340 lsls r3, r3, r2 + 163:stm32lib/src/stm32f10x_gpio.c **** + 164:stm32lib/src/stm32f10x_gpio.c **** /* Write the mode configuration in the corresponding bits */ + 165:stm32lib/src/stm32f10x_gpio.c **** tmpreg |= (currentmode << pos); + 77 .loc 1 165 0 + 78 0038 17FA02F2 lsls r2, r7, r2 + 79 .loc 1 162 0 + 80 003c 24EA0303 bic r3, r4, r3 + 81 .LVL8: + 166:stm32lib/src/stm32f10x_gpio.c **** + 167:stm32lib/src/stm32f10x_gpio.c **** /* Reset the corresponding ODR bit */ + 168:stm32lib/src/stm32f10x_gpio.c **** if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD) + 82 .loc 1 168 0 + 83 0040 282D cmp r5, #40 + 84 .loc 1 165 0 + 85 0042 43EA0204 orr r4, r3, r2 + 86 .LVL9: + 87 .loc 1 168 0 + 88 0046 01D1 bne .L5 + 169:stm32lib/src/stm32f10x_gpio.c **** { + 170:stm32lib/src/stm32f10x_gpio.c **** GPIOx->BRR = (((u32)0x01) << pinpos); + 89 .loc 1 170 0 + 90 0048 4161 str r1, [r0, #20] + 91 004a 02E0 b .L4 + 92 .L5: + 171:stm32lib/src/stm32f10x_gpio.c **** } + 172:stm32lib/src/stm32f10x_gpio.c **** else + 173:stm32lib/src/stm32f10x_gpio.c **** { + 174:stm32lib/src/stm32f10x_gpio.c **** /* Set the corresponding ODR bit */ + 175:stm32lib/src/stm32f10x_gpio.c **** if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU) + 93 .loc 1 175 0 + 94 004c 482D cmp r5, #72 + 176:stm32lib/src/stm32f10x_gpio.c **** { + 177:stm32lib/src/stm32f10x_gpio.c **** GPIOx->BSRR = (((u32)0x01) << pinpos); + 95 .loc 1 177 0 + 96 004e 08BF it eq + 97 0050 0161 streq r1, [r0, #16] + 98 .LVL10: + 99 .L4: + 100 .loc 1 151 0 + 101 0052 0CF1010C add ip, ip, #1 + 102 0056 BCF1080F cmp ip, #8 + 103 005a E2D1 bne .L6 + 178:stm32lib/src/stm32f10x_gpio.c **** } + 179:stm32lib/src/stm32f10x_gpio.c **** } + 180:stm32lib/src/stm32f10x_gpio.c **** } + 181:stm32lib/src/stm32f10x_gpio.c **** } + 182:stm32lib/src/stm32f10x_gpio.c **** GPIOx->CRL = tmpreg; + 104 .loc 1 182 0 + 105 005c 0460 str r4, [r0, #0] + 106 .LVL11: + 107 .L3: + 183:stm32lib/src/stm32f10x_gpio.c **** } + 184:stm32lib/src/stm32f10x_gpio.c **** + 185:stm32lib/src/stm32f10x_gpio.c **** /*---------------------------- GPIO CRH Configuration ------------------------*/ + 186:stm32lib/src/stm32f10x_gpio.c **** /* Configure the eight high port pins */ + 187:stm32lib/src/stm32f10x_gpio.c **** if (GPIO_InitStruct->GPIO_Pin > 0x00FF) + 108 .loc 1 187 0 + 109 005e FF2E cmp r6, #255 + 110 0060 21D9 bls .L11 + 188:stm32lib/src/stm32f10x_gpio.c **** { + 189:stm32lib/src/stm32f10x_gpio.c **** tmpreg = GPIOx->CRH; + 111 .loc 1 189 0 + 112 0062 4468 ldr r4, [r0, #4] + 113 .LVL12: + 114 0064 4FF0000C mov ip, #0 + 115 .LVL13: + 116 .L10: + 190:stm32lib/src/stm32f10x_gpio.c **** for (pinpos = 0x00; pinpos < 0x08; pinpos++) + 191:stm32lib/src/stm32f10x_gpio.c **** { + 192:stm32lib/src/stm32f10x_gpio.c **** pos = (((u32)0x01) << (pinpos + 0x08)); + 117 .loc 1 192 0 + 118 0068 0123 movs r3, #1 + 119 .LVL14: + 120 006a 0CF10802 add r2, ip, #8 + 121 006e 9340 lsls r3, r3, r2 + 122 .LVL15: + 193:stm32lib/src/stm32f10x_gpio.c **** /* Get the port pins position */ + 194:stm32lib/src/stm32f10x_gpio.c **** currentpin = ((GPIO_InitStruct->GPIO_Pin) & pos); + 123 .loc 1 194 0 + 124 0070 03EA0601 and r1, r3, r6 + 125 .LVL16: + 195:stm32lib/src/stm32f10x_gpio.c **** if (currentpin == pos) + 126 .loc 1 195 0 + 127 0074 9942 cmp r1, r3 + 128 0076 10D1 bne .L8 + 196:stm32lib/src/stm32f10x_gpio.c **** { + 197:stm32lib/src/stm32f10x_gpio.c **** pos = pinpos << 2; + 198:stm32lib/src/stm32f10x_gpio.c **** /* Clear the corresponding high control register bits */ + 199:stm32lib/src/stm32f10x_gpio.c **** pinmask = ((u32)0x0F) << pos; + 129 .loc 1 199 0 + 130 0078 4FEA8C02 lsl r2, ip, #2 + 200:stm32lib/src/stm32f10x_gpio.c **** tmpreg &= ~pinmask; + 131 .loc 1 200 0 + 132 007c 0F23 movs r3, #15 + 133 .LVL17: + 134 007e 9340 lsls r3, r3, r2 + 201:stm32lib/src/stm32f10x_gpio.c **** + 202:stm32lib/src/stm32f10x_gpio.c **** /* Write the mode configuration in the corresponding bits */ + 203:stm32lib/src/stm32f10x_gpio.c **** tmpreg |= (currentmode << pos); + 135 .loc 1 203 0 + 136 0080 17FA02F2 lsls r2, r7, r2 + 137 .loc 1 200 0 + 138 0084 24EA0303 bic r3, r4, r3 + 139 .LVL18: + 204:stm32lib/src/stm32f10x_gpio.c **** + 205:stm32lib/src/stm32f10x_gpio.c **** /* Reset the corresponding ODR bit */ + 206:stm32lib/src/stm32f10x_gpio.c **** if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD) + 140 .loc 1 206 0 + 141 0088 282D cmp r5, #40 + 142 .loc 1 203 0 + 143 008a 43EA0204 orr r4, r3, r2 + 144 .LVL19: + 145 .loc 1 206 0 + 146 008e 01D1 bne .L9 + 207:stm32lib/src/stm32f10x_gpio.c **** { + 208:stm32lib/src/stm32f10x_gpio.c **** GPIOx->BRR = (((u32)0x01) << (pinpos + 0x08)); + 147 .loc 1 208 0 + 148 0090 4161 str r1, [r0, #20] + 149 0092 02E0 b .L8 + 150 .L9: + 209:stm32lib/src/stm32f10x_gpio.c **** } + 210:stm32lib/src/stm32f10x_gpio.c **** /* Set the corresponding ODR bit */ + 211:stm32lib/src/stm32f10x_gpio.c **** if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU) + 151 .loc 1 211 0 + 152 0094 482D cmp r5, #72 + 212:stm32lib/src/stm32f10x_gpio.c **** { + 213:stm32lib/src/stm32f10x_gpio.c **** GPIOx->BSRR = (((u32)0x01) << (pinpos + 0x08)); + 153 .loc 1 213 0 + 154 0096 08BF it eq + 155 0098 0161 streq r1, [r0, #16] + 156 .LVL20: + 157 .L8: + 158 .loc 1 190 0 + 159 009a 0CF1010C add ip, ip, #1 + 160 009e BCF1080F cmp ip, #8 + 161 00a2 E1D1 bne .L10 + 214:stm32lib/src/stm32f10x_gpio.c **** } + 215:stm32lib/src/stm32f10x_gpio.c **** } + 216:stm32lib/src/stm32f10x_gpio.c **** } + 217:stm32lib/src/stm32f10x_gpio.c **** GPIOx->CRH = tmpreg; + 162 .loc 1 217 0 + 163 00a4 4460 str r4, [r0, #4] + 164 .LVL21: + 165 .L11: + 218:stm32lib/src/stm32f10x_gpio.c **** } + 219:stm32lib/src/stm32f10x_gpio.c **** } + 166 .loc 1 219 0 + 167 00a6 F0BD pop {r4, r5, r6, r7, pc} + 168 .LFE25: + 170 .align 2 + 171 .global GPIO_StructInit + 172 .thumb + 173 .thumb_func + 175 GPIO_StructInit: + 176 .LFB26: + 220:stm32lib/src/stm32f10x_gpio.c **** + 221:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 222:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_StructInit + 223:stm32lib/src/stm32f10x_gpio.c **** * Description : Fills each GPIO_InitStruct member with its default value. + 224:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIO_InitStruct : pointer to a GPIO_InitTypeDef structure + 225:stm32lib/src/stm32f10x_gpio.c **** * which will be initialized. + 226:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 227:stm32lib/src/stm32f10x_gpio.c **** * Return : None + 228:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 229:stm32lib/src/stm32f10x_gpio.c **** void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct) + 230:stm32lib/src/stm32f10x_gpio.c **** { + 177 .loc 1 230 0 + 178 @ args = 0, pretend = 0, frame = 0 + 179 @ frame_needed = 0, uses_anonymous_args = 0 + 180 @ link register save eliminated. + 181 .LVL22: + 231:stm32lib/src/stm32f10x_gpio.c **** /* Reset GPIO init structure parameters values */ + 232:stm32lib/src/stm32f10x_gpio.c **** GPIO_InitStruct->GPIO_Pin = GPIO_Pin_All; + 182 .loc 1 232 0 + 183 00a8 4FF0FF33 mov r3, #-1 @ movhi + 184 00ac 0380 strh r3, [r0, #0] @ movhi + 233:stm32lib/src/stm32f10x_gpio.c **** GPIO_InitStruct->GPIO_Speed = GPIO_Speed_2MHz; + 185 .loc 1 233 0 + 186 00ae 0223 movs r3, #2 + 187 00b0 8370 strb r3, [r0, #2] + 234:stm32lib/src/stm32f10x_gpio.c **** GPIO_InitStruct->GPIO_Mode = GPIO_Mode_IN_FLOATING; + 188 .loc 1 234 0 + 189 00b2 DB18 adds r3, r3, r3 + 190 00b4 C370 strb r3, [r0, #3] + 235:stm32lib/src/stm32f10x_gpio.c **** } + 191 .loc 1 235 0 + 192 00b6 7047 bx lr + 193 .LFE26: + 195 .align 2 + 196 .global GPIO_ReadInputDataBit + 197 .thumb + 198 .thumb_func + 200 GPIO_ReadInputDataBit: + 201 .LFB27: + 236:stm32lib/src/stm32f10x_gpio.c **** + 237:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 238:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_ReadInputDataBit + 239:stm32lib/src/stm32f10x_gpio.c **** * Description : Reads the specified input port pin. + 240:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral. + 241:stm32lib/src/stm32f10x_gpio.c **** * : - GPIO_Pin: specifies the port bit to read. + 242:stm32lib/src/stm32f10x_gpio.c **** * This parameter can be GPIO_Pin_x where x can be (0..15). + 243:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 244:stm32lib/src/stm32f10x_gpio.c **** * Return : The input port pin value. + 245:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 246:stm32lib/src/stm32f10x_gpio.c **** u8 GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin) + 247:stm32lib/src/stm32f10x_gpio.c **** { + 202 .loc 1 247 0 + 203 @ args = 0, pretend = 0, frame = 0 + 204 @ frame_needed = 0, uses_anonymous_args = 0 + 205 @ link register save eliminated. + 206 .LVL23: + 248:stm32lib/src/stm32f10x_gpio.c **** u8 bitstatus = 0x00; + 249:stm32lib/src/stm32f10x_gpio.c **** + 250:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 251:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + 252:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + 253:stm32lib/src/stm32f10x_gpio.c **** + 254:stm32lib/src/stm32f10x_gpio.c **** if ((GPIOx->IDR & GPIO_Pin) != (u32)Bit_RESET) + 207 .loc 1 254 0 + 208 00b8 8368 ldr r3, [r0, #8] + 209 00ba 1942 tst r1, r3 + 255:stm32lib/src/stm32f10x_gpio.c **** { + 256:stm32lib/src/stm32f10x_gpio.c **** bitstatus = (u8)Bit_SET; + 257:stm32lib/src/stm32f10x_gpio.c **** } + 258:stm32lib/src/stm32f10x_gpio.c **** else + 259:stm32lib/src/stm32f10x_gpio.c **** { + 260:stm32lib/src/stm32f10x_gpio.c **** bitstatus = (u8)Bit_RESET; + 261:stm32lib/src/stm32f10x_gpio.c **** } + 262:stm32lib/src/stm32f10x_gpio.c **** return bitstatus; + 263:stm32lib/src/stm32f10x_gpio.c **** } + 210 .loc 1 263 0 + 211 00bc 0CBF ite eq + 212 00be 0020 moveq r0, #0 + 213 00c0 0120 movne r0, #1 + 214 .LVL24: + 215 00c2 7047 bx lr + 216 .LFE27: + 218 .align 2 + 219 .global GPIO_ReadInputData + 220 .thumb + 221 .thumb_func + 223 GPIO_ReadInputData: + 224 .LFB28: + 264:stm32lib/src/stm32f10x_gpio.c **** + 265:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 266:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_ReadInputData + 267:stm32lib/src/stm32f10x_gpio.c **** * Description : Reads the specified GPIO input data port. + 268:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral. + 269:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 270:stm32lib/src/stm32f10x_gpio.c **** * Return : GPIO input data port value. + 271:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 272:stm32lib/src/stm32f10x_gpio.c **** u16 GPIO_ReadInputData(GPIO_TypeDef* GPIOx) + 273:stm32lib/src/stm32f10x_gpio.c **** { + 225 .loc 1 273 0 + 226 @ args = 0, pretend = 0, frame = 0 + 227 @ frame_needed = 0, uses_anonymous_args = 0 + 228 @ link register save eliminated. + 229 .LVL25: + 274:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 275:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + 276:stm32lib/src/stm32f10x_gpio.c **** + 277:stm32lib/src/stm32f10x_gpio.c **** return ((u16)GPIOx->IDR); + 230 .loc 1 277 0 + 231 00c4 8068 ldr r0, [r0, #8] + 232 .LVL26: + 278:stm32lib/src/stm32f10x_gpio.c **** } + 233 .loc 1 278 0 + 234 00c6 80B2 uxth r0, r0 + 235 00c8 7047 bx lr + 236 .LFE28: + 238 00ca 00BF .align 2 + 239 .global GPIO_ReadOutputDataBit + 240 .thumb + 241 .thumb_func + 243 GPIO_ReadOutputDataBit: + 244 .LFB29: + 279:stm32lib/src/stm32f10x_gpio.c **** + 280:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 281:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_ReadOutputDataBit + 282:stm32lib/src/stm32f10x_gpio.c **** * Description : Reads the specified output data port bit. + 283:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral. + 284:stm32lib/src/stm32f10x_gpio.c **** * : - GPIO_Pin: specifies the port bit to read. + 285:stm32lib/src/stm32f10x_gpio.c **** * This parameter can be GPIO_Pin_x where x can be (0..15). + 286:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 287:stm32lib/src/stm32f10x_gpio.c **** * Return : The output port pin value. + 288:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 289:stm32lib/src/stm32f10x_gpio.c **** u8 GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin) + 290:stm32lib/src/stm32f10x_gpio.c **** { + 245 .loc 1 290 0 + 246 @ args = 0, pretend = 0, frame = 0 + 247 @ frame_needed = 0, uses_anonymous_args = 0 + 248 @ link register save eliminated. + 249 .LVL27: + 291:stm32lib/src/stm32f10x_gpio.c **** u8 bitstatus = 0x00; + 292:stm32lib/src/stm32f10x_gpio.c **** + 293:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 294:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + 295:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + 296:stm32lib/src/stm32f10x_gpio.c **** + 297:stm32lib/src/stm32f10x_gpio.c **** if ((GPIOx->ODR & GPIO_Pin) != (u32)Bit_RESET) + 250 .loc 1 297 0 + 251 00cc C368 ldr r3, [r0, #12] + 252 00ce 1942 tst r1, r3 + 298:stm32lib/src/stm32f10x_gpio.c **** { + 299:stm32lib/src/stm32f10x_gpio.c **** bitstatus = (u8)Bit_SET; + 300:stm32lib/src/stm32f10x_gpio.c **** } + 301:stm32lib/src/stm32f10x_gpio.c **** else + 302:stm32lib/src/stm32f10x_gpio.c **** { + 303:stm32lib/src/stm32f10x_gpio.c **** bitstatus = (u8)Bit_RESET; + 304:stm32lib/src/stm32f10x_gpio.c **** } + 305:stm32lib/src/stm32f10x_gpio.c **** return bitstatus; + 306:stm32lib/src/stm32f10x_gpio.c **** } + 253 .loc 1 306 0 + 254 00d0 0CBF ite eq + 255 00d2 0020 moveq r0, #0 + 256 00d4 0120 movne r0, #1 + 257 .LVL28: + 258 00d6 7047 bx lr + 259 .LFE29: + 261 .align 2 + 262 .global GPIO_ReadOutputData + 263 .thumb + 264 .thumb_func + 266 GPIO_ReadOutputData: + 267 .LFB30: + 307:stm32lib/src/stm32f10x_gpio.c **** + 308:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 309:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_ReadOutputData + 310:stm32lib/src/stm32f10x_gpio.c **** * Description : Reads the specified GPIO output data port. + 311:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral. + 312:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 313:stm32lib/src/stm32f10x_gpio.c **** * Return : GPIO output data port value. + 314:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 315:stm32lib/src/stm32f10x_gpio.c **** u16 GPIO_ReadOutputData(GPIO_TypeDef* GPIOx) + 316:stm32lib/src/stm32f10x_gpio.c **** { + 268 .loc 1 316 0 + 269 @ args = 0, pretend = 0, frame = 0 + 270 @ frame_needed = 0, uses_anonymous_args = 0 + 271 @ link register save eliminated. + 272 .LVL29: + 317:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 318:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + 319:stm32lib/src/stm32f10x_gpio.c **** + 320:stm32lib/src/stm32f10x_gpio.c **** return ((u16)GPIOx->ODR); + 273 .loc 1 320 0 + 274 00d8 C068 ldr r0, [r0, #12] + 275 .LVL30: + 321:stm32lib/src/stm32f10x_gpio.c **** } + 276 .loc 1 321 0 + 277 00da 80B2 uxth r0, r0 + 278 00dc 7047 bx lr + 279 .LFE30: + 281 00de 00BF .align 2 + 282 .global GPIO_SetBits + 283 .thumb + 284 .thumb_func + 286 GPIO_SetBits: + 287 .LFB31: + 322:stm32lib/src/stm32f10x_gpio.c **** + 323:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 324:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_SetBits + 325:stm32lib/src/stm32f10x_gpio.c **** * Description : Sets the selected data port bits. + 326:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral. + 327:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Pin: specifies the port bits to be written. + 328:stm32lib/src/stm32f10x_gpio.c **** * This parameter can be any combination of GPIO_Pin_x where + 329:stm32lib/src/stm32f10x_gpio.c **** * x can be (0..15). + 330:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 331:stm32lib/src/stm32f10x_gpio.c **** * Return : None + 332:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 333:stm32lib/src/stm32f10x_gpio.c **** void GPIO_SetBits(GPIO_TypeDef* GPIOx, u16 GPIO_Pin) + 334:stm32lib/src/stm32f10x_gpio.c **** { + 288 .loc 1 334 0 + 289 @ args = 0, pretend = 0, frame = 0 + 290 @ frame_needed = 0, uses_anonymous_args = 0 + 291 @ link register save eliminated. + 292 .LVL31: + 335:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 336:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + 337:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_PIN(GPIO_Pin)); + 338:stm32lib/src/stm32f10x_gpio.c **** + 339:stm32lib/src/stm32f10x_gpio.c **** GPIOx->BSRR = GPIO_Pin; + 293 .loc 1 339 0 + 294 00e0 0161 str r1, [r0, #16] + 340:stm32lib/src/stm32f10x_gpio.c **** } + 295 .loc 1 340 0 + 296 00e2 7047 bx lr + 297 .LFE31: + 299 .align 2 + 300 .global GPIO_ResetBits + 301 .thumb + 302 .thumb_func + 304 GPIO_ResetBits: + 305 .LFB32: + 341:stm32lib/src/stm32f10x_gpio.c **** + 342:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 343:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_ResetBits + 344:stm32lib/src/stm32f10x_gpio.c **** * Description : Clears the selected data port bits. + 345:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral. + 346:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Pin: specifies the port bits to be written. + 347:stm32lib/src/stm32f10x_gpio.c **** * This parameter can be any combination of GPIO_Pin_x where + 348:stm32lib/src/stm32f10x_gpio.c **** * x can be (0..15). + 349:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 350:stm32lib/src/stm32f10x_gpio.c **** * Return : None + 351:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 352:stm32lib/src/stm32f10x_gpio.c **** void GPIO_ResetBits(GPIO_TypeDef* GPIOx, u16 GPIO_Pin) + 353:stm32lib/src/stm32f10x_gpio.c **** { + 306 .loc 1 353 0 + 307 @ args = 0, pretend = 0, frame = 0 + 308 @ frame_needed = 0, uses_anonymous_args = 0 + 309 @ link register save eliminated. + 310 .LVL32: + 354:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 355:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + 356:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_PIN(GPIO_Pin)); + 357:stm32lib/src/stm32f10x_gpio.c **** + 358:stm32lib/src/stm32f10x_gpio.c **** GPIOx->BRR = GPIO_Pin; + 311 .loc 1 358 0 + 312 00e4 4161 str r1, [r0, #20] + 359:stm32lib/src/stm32f10x_gpio.c **** } + 313 .loc 1 359 0 + 314 00e6 7047 bx lr + 315 .LFE32: + 317 .align 2 + 318 .global GPIO_WriteBit + 319 .thumb + 320 .thumb_func + 322 GPIO_WriteBit: + 323 .LFB33: + 360:stm32lib/src/stm32f10x_gpio.c **** + 361:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 362:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_WriteBit + 363:stm32lib/src/stm32f10x_gpio.c **** * Description : Sets or clears the selected data port bit. + 364:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral. + 365:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Pin: specifies the port bit to be written. + 366:stm32lib/src/stm32f10x_gpio.c **** * This parameter can be one of GPIO_Pin_x where x can be (0..15). + 367:stm32lib/src/stm32f10x_gpio.c **** * - BitVal: specifies the value to be written to the selected bit. + 368:stm32lib/src/stm32f10x_gpio.c **** * This parameter can be one of the BitAction enum values: + 369:stm32lib/src/stm32f10x_gpio.c **** * - Bit_RESET: to clear the port pin + 370:stm32lib/src/stm32f10x_gpio.c **** * - Bit_SET: to set the port pin + 371:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 372:stm32lib/src/stm32f10x_gpio.c **** * Return : None + 373:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 374:stm32lib/src/stm32f10x_gpio.c **** void GPIO_WriteBit(GPIO_TypeDef* GPIOx, u16 GPIO_Pin, BitAction BitVal) + 375:stm32lib/src/stm32f10x_gpio.c **** { + 324 .loc 1 375 0 + 325 @ args = 0, pretend = 0, frame = 0 + 326 @ frame_needed = 0, uses_anonymous_args = 0 + 327 @ link register save eliminated. + 328 .LVL33: + 376:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 377:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + 378:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + 379:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_BIT_ACTION(BitVal)); + 380:stm32lib/src/stm32f10x_gpio.c **** + 381:stm32lib/src/stm32f10x_gpio.c **** if (BitVal != Bit_RESET) + 329 .loc 1 381 0 + 330 00e8 0AB1 cbz r2, .L27 + 382:stm32lib/src/stm32f10x_gpio.c **** { + 383:stm32lib/src/stm32f10x_gpio.c **** GPIOx->BSRR = GPIO_Pin; + 331 .loc 1 383 0 + 332 00ea 0161 str r1, [r0, #16] + 333 00ec 00E0 b .L29 + 334 .L27: + 384:stm32lib/src/stm32f10x_gpio.c **** } + 385:stm32lib/src/stm32f10x_gpio.c **** else + 386:stm32lib/src/stm32f10x_gpio.c **** { + 387:stm32lib/src/stm32f10x_gpio.c **** GPIOx->BRR = GPIO_Pin; + 335 .loc 1 387 0 + 336 00ee 4161 str r1, [r0, #20] + 337 .L29: + 388:stm32lib/src/stm32f10x_gpio.c **** } + 389:stm32lib/src/stm32f10x_gpio.c **** } + 338 .loc 1 389 0 + 339 00f0 7047 bx lr + 340 .LFE33: + 342 00f2 00BF .align 2 + 343 .global GPIO_Write + 344 .thumb + 345 .thumb_func + 347 GPIO_Write: + 348 .LFB34: + 390:stm32lib/src/stm32f10x_gpio.c **** + 391:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 392:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_Write + 393:stm32lib/src/stm32f10x_gpio.c **** * Description : Writes data to the specified GPIO data port. + 394:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral. + 395:stm32lib/src/stm32f10x_gpio.c **** * - PortVal: specifies the value to be written to the port output + 396:stm32lib/src/stm32f10x_gpio.c **** * data register. + 397:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 398:stm32lib/src/stm32f10x_gpio.c **** * Return : None + 399:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 400:stm32lib/src/stm32f10x_gpio.c **** void GPIO_Write(GPIO_TypeDef* GPIOx, u16 PortVal) + 401:stm32lib/src/stm32f10x_gpio.c **** { + 349 .loc 1 401 0 + 350 @ args = 0, pretend = 0, frame = 0 + 351 @ frame_needed = 0, uses_anonymous_args = 0 + 352 @ link register save eliminated. + 353 .LVL34: + 402:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 403:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + 404:stm32lib/src/stm32f10x_gpio.c **** + 405:stm32lib/src/stm32f10x_gpio.c **** GPIOx->ODR = PortVal; + 354 .loc 1 405 0 + 355 00f4 C160 str r1, [r0, #12] + 406:stm32lib/src/stm32f10x_gpio.c **** } + 356 .loc 1 406 0 + 357 00f6 7047 bx lr + 358 .LFE34: + 360 .align 2 + 361 .global GPIO_PinLockConfig + 362 .thumb + 363 .thumb_func + 365 GPIO_PinLockConfig: + 366 .LFB35: + 407:stm32lib/src/stm32f10x_gpio.c **** + 408:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 409:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_PinLockConfig + 410:stm32lib/src/stm32f10x_gpio.c **** * Description : Locks GPIO Pins configuration registers. + 411:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIOx: where x can be (A..G) to select the GPIO peripheral. + 412:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Pin: specifies the port bit to be written. + 413:stm32lib/src/stm32f10x_gpio.c **** * This parameter can be any combination of GPIO_Pin_x where + 414:stm32lib/src/stm32f10x_gpio.c **** * x can be (0..15). + 415:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 416:stm32lib/src/stm32f10x_gpio.c **** * Return : None + 417:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 418:stm32lib/src/stm32f10x_gpio.c **** void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, u16 GPIO_Pin) + 419:stm32lib/src/stm32f10x_gpio.c **** { + 367 .loc 1 419 0 + 368 @ args = 0, pretend = 0, frame = 0 + 369 @ frame_needed = 0, uses_anonymous_args = 0 + 370 @ link register save eliminated. + 371 .LVL35: + 420:stm32lib/src/stm32f10x_gpio.c **** u32 tmp = 0x00010000; + 421:stm32lib/src/stm32f10x_gpio.c **** + 422:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 423:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + 424:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_PIN(GPIO_Pin)); + 425:stm32lib/src/stm32f10x_gpio.c **** + 426:stm32lib/src/stm32f10x_gpio.c **** tmp |= GPIO_Pin; + 372 .loc 1 426 0 + 373 00f8 41F48033 orr r3, r1, #65536 + 374 .LVL36: + 427:stm32lib/src/stm32f10x_gpio.c **** /* Set LCKK bit */ + 428:stm32lib/src/stm32f10x_gpio.c **** GPIOx->LCKR = tmp; + 375 .loc 1 428 0 + 376 00fc 8361 str r3, [r0, #24] + 429:stm32lib/src/stm32f10x_gpio.c **** /* Reset LCKK bit */ + 430:stm32lib/src/stm32f10x_gpio.c **** GPIOx->LCKR = GPIO_Pin; + 377 .loc 1 430 0 + 378 00fe 8161 str r1, [r0, #24] + 431:stm32lib/src/stm32f10x_gpio.c **** /* Set LCKK bit */ + 432:stm32lib/src/stm32f10x_gpio.c **** GPIOx->LCKR = tmp; + 379 .loc 1 432 0 + 380 0100 8361 str r3, [r0, #24] + 433:stm32lib/src/stm32f10x_gpio.c **** /* Read LCKK bit*/ + 434:stm32lib/src/stm32f10x_gpio.c **** tmp = GPIOx->LCKR; + 381 .loc 1 434 0 + 382 0102 8369 ldr r3, [r0, #24] + 383 .LVL37: + 435:stm32lib/src/stm32f10x_gpio.c **** /* Read LCKK bit*/ + 436:stm32lib/src/stm32f10x_gpio.c **** tmp = GPIOx->LCKR; + 384 .loc 1 436 0 + 385 0104 8369 ldr r3, [r0, #24] + 386 .LVL38: + 437:stm32lib/src/stm32f10x_gpio.c **** } + 387 .loc 1 437 0 + 388 0106 7047 bx lr + 389 .LFE35: + 391 .align 2 + 392 .global GPIO_EventOutputConfig + 393 .thumb + 394 .thumb_func + 396 GPIO_EventOutputConfig: + 397 .LFB36: + 438:stm32lib/src/stm32f10x_gpio.c **** + 439:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 440:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_EventOutputConfig + 441:stm32lib/src/stm32f10x_gpio.c **** * Description : Selects the GPIO pin used as Event output. + 442:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIO_PortSource: selects the GPIO port to be used as source + 443:stm32lib/src/stm32f10x_gpio.c **** * for Event output. + 444:stm32lib/src/stm32f10x_gpio.c **** * This parameter can be GPIO_PortSourceGPIOx where x can be + 445:stm32lib/src/stm32f10x_gpio.c **** * (A..E). + 446:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_PinSource: specifies the pin for the Event output. + 447:stm32lib/src/stm32f10x_gpio.c **** * This parameter can be GPIO_PinSourcex where x can be (0..15). + 448:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 449:stm32lib/src/stm32f10x_gpio.c **** * Return : None + 450:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 451:stm32lib/src/stm32f10x_gpio.c **** void GPIO_EventOutputConfig(u8 GPIO_PortSource, u8 GPIO_PinSource) + 452:stm32lib/src/stm32f10x_gpio.c **** { + 398 .loc 1 452 0 + 399 @ args = 0, pretend = 0, frame = 0 + 400 @ frame_needed = 0, uses_anonymous_args = 0 + 401 .LVL39: + 402 0108 10B5 push {r4, lr} + 403 .LCFI1: + 453:stm32lib/src/stm32f10x_gpio.c **** u32 tmpreg = 0x00; + 454:stm32lib/src/stm32f10x_gpio.c **** + 455:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 456:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_EVENTOUT_PORT_SOURCE(GPIO_PortSource)); + 457:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource)); + 458:stm32lib/src/stm32f10x_gpio.c **** + 459:stm32lib/src/stm32f10x_gpio.c **** tmpreg = AFIO->EVCR; + 404 .loc 1 459 0 + 405 010a 054C ldr r4, .L36 + 460:stm32lib/src/stm32f10x_gpio.c **** /* Clear the PORT[6:4] and PIN[3:0] bits */ + 461:stm32lib/src/stm32f10x_gpio.c **** tmpreg &= EVCR_PORTPINCONFIG_MASK; + 406 .loc 1 461 0 + 407 010c 4FF68073 movw r3, #65408 + 408 .LVL40: + 409 .loc 1 459 0 + 410 0110 2268 ldr r2, [r4, #0] + 411 .LVL41: + 462:stm32lib/src/stm32f10x_gpio.c **** tmpreg |= (u32)GPIO_PortSource << 0x04; + 412 .loc 1 462 0 + 413 0112 41EA0011 orr r1, r1, r0, lsl #4 + 414 .LVL42: + 415 .loc 1 461 0 + 416 0116 02EA0303 and r3, r2, r3 + 417 .LVL43: + 463:stm32lib/src/stm32f10x_gpio.c **** tmpreg |= GPIO_PinSource; + 418 .loc 1 463 0 + 419 011a 1943 orrs r1, r1, r3 + 420 .LVL44: + 464:stm32lib/src/stm32f10x_gpio.c **** + 465:stm32lib/src/stm32f10x_gpio.c **** AFIO->EVCR = tmpreg; + 421 .loc 1 465 0 + 422 011c 2160 str r1, [r4, #0] + 466:stm32lib/src/stm32f10x_gpio.c **** } + 423 .loc 1 466 0 + 424 011e 10BD pop {r4, pc} + 425 .L37: + 426 .align 2 + 427 .L36: + 428 0120 00000140 .word 1073807360 + 429 .LFE36: + 431 .align 2 + 432 .global GPIO_EventOutputCmd + 433 .thumb + 434 .thumb_func + 436 GPIO_EventOutputCmd: + 437 .LFB37: + 467:stm32lib/src/stm32f10x_gpio.c **** + 468:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 469:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_EventOutputCmd + 470:stm32lib/src/stm32f10x_gpio.c **** * Description : Enables or disables the Event Output. + 471:stm32lib/src/stm32f10x_gpio.c **** * Input : - NewState: new state of the Event output. + 472:stm32lib/src/stm32f10x_gpio.c **** * This parameter can be: ENABLE or DISABLE. + 473:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 474:stm32lib/src/stm32f10x_gpio.c **** * Return : None + 475:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 476:stm32lib/src/stm32f10x_gpio.c **** void GPIO_EventOutputCmd(FunctionalState NewState) + 477:stm32lib/src/stm32f10x_gpio.c **** { + 438 .loc 1 477 0 + 439 @ args = 0, pretend = 0, frame = 0 + 440 @ frame_needed = 0, uses_anonymous_args = 0 + 441 @ link register save eliminated. + 442 .LVL45: + 478:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 479:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 480:stm32lib/src/stm32f10x_gpio.c **** + 481:stm32lib/src/stm32f10x_gpio.c **** *(vu32 *) EVCR_EVOE_BB = (u32)NewState; + 443 .loc 1 481 0 + 444 0124 014B ldr r3, .L40 + 445 0126 1860 str r0, [r3, #0] + 482:stm32lib/src/stm32f10x_gpio.c **** } + 446 .loc 1 482 0 + 447 0128 7047 bx lr + 448 .L41: + 449 012a 00BF .align 2 + 450 .L40: + 451 012c 1C002042 .word 1109393436 + 452 .LFE37: + 454 .align 2 + 455 .global GPIO_PinRemapConfig + 456 .thumb + 457 .thumb_func + 459 GPIO_PinRemapConfig: + 460 .LFB38: + 483:stm32lib/src/stm32f10x_gpio.c **** + 484:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 485:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_PinRemapConfig + 486:stm32lib/src/stm32f10x_gpio.c **** * Description : Changes the mapping of the specified pin. + 487:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIO_Remap: selects the pin to remap. + 488:stm32lib/src/stm32f10x_gpio.c **** * This parameter can be one of the following values: + 489:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap_SPI1 + 490:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap_I2C1 + 491:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap_USART1 + 492:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap_USART2 + 493:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_PartialRemap_USART3 + 494:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_FullRemap_USART3 + 495:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_PartialRemap_TIM1 + 496:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_FullRemap_TIM1 + 497:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_PartialRemap1_TIM2 + 498:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_PartialRemap2_TIM2 + 499:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_FullRemap_TIM2 + 500:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_PartialRemap_TIM3 + 501:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_FullRemap_TIM3 + 502:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap_TIM4 + 503:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap1_CAN + 504:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap2_CAN + 505:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap_PD01 + 506:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap_TIM5CH4_LSI + 507:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap_ADC1_ETRGINJ + 508:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap_ADC1_ETRGREG + 509:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap_ADC2_ETRGINJ + 510:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap_ADC2_ETRGREG + 511:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap_SWJ_NoJTRST + 512:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap_SWJ_JTAGDisable + 513:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_Remap_SWJ_Disable + 514:stm32lib/src/stm32f10x_gpio.c **** * - NewState: new state of the port pin remapping. + 515:stm32lib/src/stm32f10x_gpio.c **** * This parameter can be: ENABLE or DISABLE. + 516:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 517:stm32lib/src/stm32f10x_gpio.c **** * Return : None + 518:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 519:stm32lib/src/stm32f10x_gpio.c **** void GPIO_PinRemapConfig(u32 GPIO_Remap, FunctionalState NewState) + 520:stm32lib/src/stm32f10x_gpio.c **** { + 461 .loc 1 520 0 + 462 @ args = 0, pretend = 0, frame = 0 + 463 @ frame_needed = 0, uses_anonymous_args = 0 + 464 .LVL46: + 465 0130 30B5 push {r4, r5, lr} + 466 .LCFI2: + 521:stm32lib/src/stm32f10x_gpio.c **** u32 tmp = 0x00, tmp1 = 0x00, tmpreg = 0x00, tmpmask = 0x00; + 522:stm32lib/src/stm32f10x_gpio.c **** + 523:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 524:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_REMAP(GPIO_Remap)); + 525:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 526:stm32lib/src/stm32f10x_gpio.c **** + 527:stm32lib/src/stm32f10x_gpio.c **** tmpreg = AFIO->MAPR; + 528:stm32lib/src/stm32f10x_gpio.c **** + 529:stm32lib/src/stm32f10x_gpio.c **** tmpmask = (GPIO_Remap & DBGAFR_POSITION_MASK) >> 0x10; + 530:stm32lib/src/stm32f10x_gpio.c **** tmp = GPIO_Remap & LSB_MASK; + 531:stm32lib/src/stm32f10x_gpio.c **** + 532:stm32lib/src/stm32f10x_gpio.c **** if ((GPIO_Remap & (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) == (DBGAFR_LOCATION_MASK | DBGAFR + 467 .loc 1 532 0 + 468 0132 00F44013 and r3, r0, #3145728 + 469 .loc 1 527 0 + 470 0136 154C ldr r4, .L49 + 471 .loc 1 530 0 + 472 0138 4FEA004C lsl ip, r0, #16 + 473 .LVL47: + 474 .loc 1 532 0 + 475 013c B3F5401F cmp r3, #3145728 + 476 .loc 1 520 0 + 477 0140 0D46 mov r5, r1 + 478 .loc 1 530 0 + 479 0142 4FEA1C4C lsr ip, ip, #16 + 480 .loc 1 527 0 + 481 0146 6168 ldr r1, [r4, #4] + 482 .LVL48: + 483 .loc 1 532 0 + 484 0148 06D1 bne .L43 + 533:stm32lib/src/stm32f10x_gpio.c **** { + 534:stm32lib/src/stm32f10x_gpio.c **** tmpreg &= DBGAFR_SWJCFG_MASK; + 535:stm32lib/src/stm32f10x_gpio.c **** AFIO->MAPR &= DBGAFR_SWJCFG_MASK; + 485 .loc 1 535 0 + 486 014a 6368 ldr r3, [r4, #4] + 487 .loc 1 534 0 + 488 014c 21F07062 bic r2, r1, #251658240 + 489 .LVL49: + 490 .loc 1 535 0 + 491 0150 23F07063 bic r3, r3, #251658240 + 492 0154 6360 str r3, [r4, #4] + 493 0156 0FE0 b .L44 + 494 .LVL50: + 495 .L43: + 536:stm32lib/src/stm32f10x_gpio.c **** } + 537:stm32lib/src/stm32f10x_gpio.c **** else if ((GPIO_Remap & DBGAFR_NUMBITS_MASK) == DBGAFR_NUMBITS_MASK) + 496 .loc 1 537 0 + 497 0158 10F4801F tst r0, #1048576 + 498 015c 04D0 beq .L45 + 538:stm32lib/src/stm32f10x_gpio.c **** { + 539:stm32lib/src/stm32f10x_gpio.c **** tmp1 = ((u32)0x03) << tmpmask; + 540:stm32lib/src/stm32f10x_gpio.c **** tmpreg &= ~tmp1; + 499 .loc 1 540 0 + 500 015e C0F30342 ubfx r2, r0, #16, #4 + 501 0162 0323 movs r3, #3 + 502 0164 9340 lsls r3, r3, r2 + 503 0166 03E0 b .L48 + 504 .L45: + 541:stm32lib/src/stm32f10x_gpio.c **** tmpreg |= ~DBGAFR_SWJCFG_MASK; + 542:stm32lib/src/stm32f10x_gpio.c **** } + 543:stm32lib/src/stm32f10x_gpio.c **** else + 544:stm32lib/src/stm32f10x_gpio.c **** { + 545:stm32lib/src/stm32f10x_gpio.c **** tmpreg &= ~(tmp << ((GPIO_Remap >> 0x15)*0x10)); + 505 .loc 1 545 0 + 506 0168 430D lsrs r3, r0, #21 + 507 016a 1B01 lsls r3, r3, #4 + 508 016c 0CFA03F3 lsl r3, ip, r3 + 509 .L48: + 510 0170 21EA0303 bic r3, r1, r3 + 511 .LVL51: + 546:stm32lib/src/stm32f10x_gpio.c **** tmpreg |= ~DBGAFR_SWJCFG_MASK; + 512 .loc 1 546 0 + 513 0174 43F07062 orr r2, r3, #251658240 + 514 .LVL52: + 515 .L44: + 547:stm32lib/src/stm32f10x_gpio.c **** } + 548:stm32lib/src/stm32f10x_gpio.c **** + 549:stm32lib/src/stm32f10x_gpio.c **** if (NewState != DISABLE) + 516 .loc 1 549 0 + 517 0178 25B1 cbz r5, .L46 + 550:stm32lib/src/stm32f10x_gpio.c **** { + 551:stm32lib/src/stm32f10x_gpio.c **** tmpreg |= (tmp << ((GPIO_Remap >> 0x15)*0x10)); + 518 .loc 1 551 0 + 519 017a 430D lsrs r3, r0, #21 + 520 017c 1B01 lsls r3, r3, #4 + 521 017e 0CFA03F3 lsl r3, ip, r3 + 522 0182 1A43 orrs r2, r2, r3 + 523 .L46: + 552:stm32lib/src/stm32f10x_gpio.c **** } + 553:stm32lib/src/stm32f10x_gpio.c **** + 554:stm32lib/src/stm32f10x_gpio.c **** AFIO->MAPR = tmpreg; + 524 .loc 1 554 0 + 525 0184 014B ldr r3, .L49 + 526 0186 5A60 str r2, [r3, #4] + 555:stm32lib/src/stm32f10x_gpio.c **** } + 527 .loc 1 555 0 + 528 0188 30BD pop {r4, r5, pc} + 529 .L50: + 530 018a 00BF .align 2 + 531 .L49: + 532 018c 00000140 .word 1073807360 + 533 .LFE38: + 535 .align 2 + 536 .global GPIO_EXTILineConfig + 537 .thumb + 538 .thumb_func + 540 GPIO_EXTILineConfig: + 541 .LFB39: + 556:stm32lib/src/stm32f10x_gpio.c **** + 557:stm32lib/src/stm32f10x_gpio.c **** /******************************************************************************* + 558:stm32lib/src/stm32f10x_gpio.c **** * Function Name : GPIO_EXTILineConfig + 559:stm32lib/src/stm32f10x_gpio.c **** * Description : Selects the GPIO pin used as EXTI Line. + 560:stm32lib/src/stm32f10x_gpio.c **** * Input : - GPIO_PortSource: selects the GPIO port to be used as + 561:stm32lib/src/stm32f10x_gpio.c **** * source for EXTI lines. + 562:stm32lib/src/stm32f10x_gpio.c **** * This parameter can be GPIO_PortSourceGPIOx where x can be + 563:stm32lib/src/stm32f10x_gpio.c **** * (A..G). + 564:stm32lib/src/stm32f10x_gpio.c **** * - GPIO_PinSource: specifies the EXTI line to be configured. + 565:stm32lib/src/stm32f10x_gpio.c **** * This parameter can be GPIO_PinSourcex where x can be (0..15). + 566:stm32lib/src/stm32f10x_gpio.c **** * Output : None + 567:stm32lib/src/stm32f10x_gpio.c **** * Return : None + 568:stm32lib/src/stm32f10x_gpio.c **** *******************************************************************************/ + 569:stm32lib/src/stm32f10x_gpio.c **** void GPIO_EXTILineConfig(u8 GPIO_PortSource, u8 GPIO_PinSource) + 570:stm32lib/src/stm32f10x_gpio.c **** { + 542 .loc 1 570 0 + 543 @ args = 0, pretend = 0, frame = 0 + 544 @ frame_needed = 0, uses_anonymous_args = 0 + 545 .LVL53: + 546 0190 30B5 push {r4, r5, lr} + 547 .LCFI3: + 571:stm32lib/src/stm32f10x_gpio.c **** u32 tmp = 0x00; + 572:stm32lib/src/stm32f10x_gpio.c **** + 573:stm32lib/src/stm32f10x_gpio.c **** /* Check the parameters */ + 574:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_EXTI_PORT_SOURCE(GPIO_PortSource)); + 575:stm32lib/src/stm32f10x_gpio.c **** assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource)); + 576:stm32lib/src/stm32f10x_gpio.c **** + 577:stm32lib/src/stm32f10x_gpio.c **** tmp = ((u32)0x0F) << (0x04 * (GPIO_PinSource & (u8)0x03)); + 548 .loc 1 577 0 + 549 0192 01F00305 and r5, r1, #3 + 550 0196 AD00 lsls r5, r5, #2 + 578:stm32lib/src/stm32f10x_gpio.c **** + 579:stm32lib/src/stm32f10x_gpio.c **** AFIO->EXTICR[GPIO_PinSource >> 0x02] &= ~tmp; + 551 .loc 1 579 0 + 552 0198 0F23 movs r3, #15 + 553 019a AB40 lsls r3, r3, r5 + 580:stm32lib/src/stm32f10x_gpio.c **** AFIO->EXTICR[GPIO_PinSource >> 0x02] |= (((u32)GPIO_PortSource) << (0x04 * (GPIO_PinSource & (u8) + 554 .loc 1 580 0 + 555 019c A840 lsls r0, r0, r5 + 556 .LVL54: + 557 .loc 1 579 0 + 558 019e 074C ldr r4, .L53 + 559 01a0 8908 lsrs r1, r1, #2 + 560 .LVL55: + 561 01a2 0231 adds r1, r1, #2 + 562 01a4 54F82120 ldr r2, [r4, r1, lsl #2] + 563 01a8 22EA0302 bic r2, r2, r3 + 564 01ac 44F82120 str r2, [r4, r1, lsl #2] + 565 .loc 1 580 0 + 566 01b0 54F82130 ldr r3, [r4, r1, lsl #2] + 567 01b4 1843 orrs r0, r0, r3 + 568 01b6 44F82100 str r0, [r4, r1, lsl #2] + 581:stm32lib/src/stm32f10x_gpio.c **** } + 569 .loc 1 581 0 + 570 01ba 30BD pop {r4, r5, pc} + 571 .L54: + 572 .align 2 + 573 .L53: + 574 01bc 00000140 .word 1073807360 + 575 .LFE39: + 577 .align 2 + 578 .global GPIO_AFIODeInit + 579 .thumb + 580 .thumb_func + 582 GPIO_AFIODeInit: + 583 .LFB24: + 584 .loc 1 108 0 + 585 @ args = 0, pretend = 0, frame = 0 + 586 @ frame_needed = 0, uses_anonymous_args = 0 + 587 .loc 1 109 0 + 588 01c0 0120 movs r0, #1 + 589 01c2 0146 mov r1, r0 + 590 .loc 1 108 0 + 591 01c4 10B5 push {r4, lr} + 592 .LCFI4: + 593 .loc 1 109 0 + 594 01c6 FFF7FEFF bl RCC_APB2PeriphResetCmd + 595 .loc 1 110 0 + 596 01ca 0120 movs r0, #1 + 597 01cc 0021 movs r1, #0 + 598 01ce FFF7FEFF bl RCC_APB2PeriphResetCmd + 599 .loc 1 111 0 + 600 01d2 10BD pop {r4, pc} + 601 .LFE24: + 603 .align 2 + 604 .global GPIO_DeInit + 605 .thumb + 606 .thumb_func + 608 GPIO_DeInit: + 609 .LFB23: + 610 .loc 1 52 0 + 611 @ args = 0, pretend = 0, frame = 8 + 612 @ frame_needed = 0, uses_anonymous_args = 0 + 613 .LVL56: + 614 01d4 07B5 push {r0, r1, r2, lr} + 615 .LCFI5: + 616 .LVL57: + 617 .loc 1 56 0 + 618 01d6 264B ldr r3, .L71 + 619 .loc 1 52 0 + 620 01d8 0190 str r0, [sp, #4] + 621 .LVL58: + 622 .loc 1 56 0 + 623 01da 9842 cmp r0, r3 + 624 .LVL59: + 625 01dc 2BD0 beq .L62 + 626 01de 0CD8 bhi .L66 + 627 01e0 A3F50063 sub r3, r3, #2048 + 628 01e4 9842 cmp r0, r3 + 629 01e6 1AD0 beq .L60 + 630 01e8 03F58063 add r3, r3, #1024 + 631 01ec 9842 cmp r0, r3 + 632 01ee 1CD0 beq .L61 + 633 01f0 A3F50063 sub r3, r3, #2048 + 634 01f4 9842 cmp r0, r3 + 635 01f6 3AD1 bne .L67 + 636 01f8 0BE0 b .L69 + 637 .L66: + 638 01fa 1E4B ldr r3, .L71+4 + 639 01fc 9842 cmp r0, r3 + 640 01fe 26D0 beq .L64 + 641 0200 03F58063 add r3, r3, #1024 + 642 0204 9842 cmp r0, r3 + 643 0206 28D0 beq .L65 + 644 0208 A3F50063 sub r3, r3, #2048 + 645 020c 9842 cmp r0, r3 + 646 020e 2ED1 bne .L67 + 647 0210 17E0 b .L70 + 648 .L69: + 649 .loc 1 59 0 + 650 0212 0420 movs r0, #4 + 651 0214 0121 movs r1, #1 + 652 0216 FFF7FEFF bl RCC_APB2PeriphResetCmd + 653 .loc 1 60 0 + 654 021a 0420 movs r0, #4 + 655 021c 24E0 b .L68 + 656 .L60: + 657 .loc 1 64 0 + 658 021e 0820 movs r0, #8 + 659 0220 0121 movs r1, #1 + 660 0222 FFF7FEFF bl RCC_APB2PeriphResetCmd + 661 .loc 1 65 0 + 662 0226 0820 movs r0, #8 + 663 0228 1EE0 b .L68 + 664 .L61: + 665 .loc 1 69 0 + 666 022a 1020 movs r0, #16 + 667 022c 0121 movs r1, #1 + 668 022e FFF7FEFF bl RCC_APB2PeriphResetCmd + 669 .loc 1 70 0 + 670 0232 1020 movs r0, #16 + 671 0234 18E0 b .L68 + 672 .L62: + 673 .loc 1 74 0 + 674 0236 2020 movs r0, #32 + 675 0238 0121 movs r1, #1 + 676 023a FFF7FEFF bl RCC_APB2PeriphResetCmd + 677 .loc 1 75 0 + 678 023e 2020 movs r0, #32 + 679 0240 12E0 b .L68 + 680 .L70: + 681 .loc 1 79 0 + 682 0242 4020 movs r0, #64 + 683 0244 0121 movs r1, #1 + 684 0246 FFF7FEFF bl RCC_APB2PeriphResetCmd + 685 .loc 1 80 0 + 686 024a 4020 movs r0, #64 + 687 024c 0CE0 b .L68 + 688 .L64: + 689 .loc 1 84 0 + 690 024e 8020 movs r0, #128 + 691 0250 0121 movs r1, #1 + 692 0252 FFF7FEFF bl RCC_APB2PeriphResetCmd + 693 .loc 1 85 0 + 694 0256 8020 movs r0, #128 + 695 0258 06E0 b .L68 + 696 .L65: + 697 .loc 1 89 0 + 698 025a 4FF48070 mov r0, #256 + 699 025e 0121 movs r1, #1 + 700 0260 FFF7FEFF bl RCC_APB2PeriphResetCmd + 701 .loc 1 90 0 + 702 0264 4FF48070 mov r0, #256 + 703 .L68: + 704 0268 0021 movs r1, #0 + 705 026a FFF7FEFF bl RCC_APB2PeriphResetCmd + 706 .L67: + 707 .loc 1 96 0 + 708 026e 0EBD pop {r1, r2, r3, pc} + 709 .L72: + 710 .align 2 + 711 .L71: + 712 0270 00140140 .word 1073812480 + 713 0274 001C0140 .word 1073814528 + 714 .LFE23: + 930 .Letext0: +DEFINED SYMBOLS + *ABS*:00000000 stm32f10x_gpio.c + /tmp/ccT67nMl.s:22 .text:00000000 $t + /tmp/ccT67nMl.s:27 .text:00000000 GPIO_Init + /tmp/ccT67nMl.s:175 .text:000000a8 GPIO_StructInit + /tmp/ccT67nMl.s:200 .text:000000b8 GPIO_ReadInputDataBit + /tmp/ccT67nMl.s:223 .text:000000c4 GPIO_ReadInputData + /tmp/ccT67nMl.s:243 .text:000000cc GPIO_ReadOutputDataBit + /tmp/ccT67nMl.s:266 .text:000000d8 GPIO_ReadOutputData + /tmp/ccT67nMl.s:286 .text:000000e0 GPIO_SetBits + /tmp/ccT67nMl.s:304 .text:000000e4 GPIO_ResetBits + /tmp/ccT67nMl.s:322 .text:000000e8 GPIO_WriteBit + /tmp/ccT67nMl.s:347 .text:000000f4 GPIO_Write + /tmp/ccT67nMl.s:365 .text:000000f8 GPIO_PinLockConfig + /tmp/ccT67nMl.s:396 .text:00000108 GPIO_EventOutputConfig + /tmp/ccT67nMl.s:428 .text:00000120 $d + /tmp/ccT67nMl.s:431 .text:00000124 $t + /tmp/ccT67nMl.s:436 .text:00000124 GPIO_EventOutputCmd + /tmp/ccT67nMl.s:451 .text:0000012c $d + /tmp/ccT67nMl.s:454 .text:00000130 $t + /tmp/ccT67nMl.s:459 .text:00000130 GPIO_PinRemapConfig + /tmp/ccT67nMl.s:532 .text:0000018c $d + /tmp/ccT67nMl.s:535 .text:00000190 $t + /tmp/ccT67nMl.s:540 .text:00000190 GPIO_EXTILineConfig + /tmp/ccT67nMl.s:574 .text:000001bc $d + /tmp/ccT67nMl.s:577 .text:000001c0 $t + /tmp/ccT67nMl.s:582 .text:000001c0 GPIO_AFIODeInit + /tmp/ccT67nMl.s:608 .text:000001d4 GPIO_DeInit + /tmp/ccT67nMl.s:712 .text:00000270 $d + +UNDEFINED SYMBOLS +RCC_APB2PeriphResetCmd diff --git a/src/stm32lib/src/stm32f10x_i2c.c b/src/stm32lib/src/stm32f10x_i2c.c new file mode 100644 index 0000000..360f71d --- /dev/null +++ b/src/stm32lib/src/stm32f10x_i2c.c @@ -0,0 +1,1216 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_i2c.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the I2C firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_i2c.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* I2C SPE mask */
+#define CR1_PE_Set ((u16)0x0001)
+#define CR1_PE_Reset ((u16)0xFFFE)
+
+/* I2C START mask */
+#define CR1_START_Set ((u16)0x0100)
+#define CR1_START_Reset ((u16)0xFEFF)
+
+/* I2C STOP mask */
+#define CR1_STOP_Set ((u16)0x0200)
+#define CR1_STOP_Reset ((u16)0xFDFF)
+
+/* I2C ACK mask */
+#define CR1_ACK_Set ((u16)0x0400)
+#define CR1_ACK_Reset ((u16)0xFBFF)
+
+/* I2C ENGC mask */
+#define CR1_ENGC_Set ((u16)0x0040)
+#define CR1_ENGC_Reset ((u16)0xFFBF)
+
+/* I2C SWRST mask */
+#define CR1_SWRST_Set ((u16)0x8000)
+#define CR1_SWRST_Reset ((u16)0x7FFF)
+
+/* I2C PEC mask */
+#define CR1_PEC_Set ((u16)0x1000)
+#define CR1_PEC_Reset ((u16)0xEFFF)
+
+/* I2C ENPEC mask */
+#define CR1_ENPEC_Set ((u16)0x0020)
+#define CR1_ENPEC_Reset ((u16)0xFFDF)
+
+/* I2C ENARP mask */
+#define CR1_ENARP_Set ((u16)0x0010)
+#define CR1_ENARP_Reset ((u16)0xFFEF)
+
+/* I2C NOSTRETCH mask */
+#define CR1_NOSTRETCH_Set ((u16)0x0080)
+#define CR1_NOSTRETCH_Reset ((u16)0xFF7F)
+
+/* I2C registers Masks */
+#define CR1_CLEAR_Mask ((u16)0xFBF5)
+
+/* I2C DMAEN mask */
+#define CR2_DMAEN_Set ((u16)0x0800)
+#define CR2_DMAEN_Reset ((u16)0xF7FF)
+
+/* I2C LAST mask */
+#define CR2_LAST_Set ((u16)0x1000)
+#define CR2_LAST_Reset ((u16)0xEFFF)
+
+/* I2C FREQ mask */
+#define CR2_FREQ_Reset ((u16)0xFFC0)
+
+/* I2C ADD0 mask */
+#define OAR1_ADD0_Set ((u16)0x0001)
+#define OAR1_ADD0_Reset ((u16)0xFFFE)
+
+/* I2C ENDUAL mask */
+#define OAR2_ENDUAL_Set ((u16)0x0001)
+#define OAR2_ENDUAL_Reset ((u16)0xFFFE)
+
+/* I2C ADD2 mask */
+#define OAR2_ADD2_Reset ((u16)0xFF01)
+
+/* I2C F/S mask */
+#define CCR_FS_Set ((u16)0x8000)
+
+/* I2C CCR mask */
+#define CCR_CCR_Set ((u16)0x0FFF)
+
+/* I2C FLAG mask */
+#define FLAG_Mask ((u32)0x00FFFFFF)
+
+/* I2C Interrupt Enable mask */
+#define ITEN_Mask ((u32)0x07000000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : I2C_DeInit
+* Description : Deinitializes the I2Cx peripheral registers to their default
+* reset values.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_DeInit(I2C_TypeDef* I2Cx)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+ switch (*(u32*)&I2Cx)
+ {
+ case I2C1_BASE:
+ /* Enable I2C1 reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, ENABLE);
+ /* Release I2C1 from reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, DISABLE);
+ break;
+
+ case I2C2_BASE:
+ /* Enable I2C2 reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, ENABLE);
+ /* Release I2C2 from reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, DISABLE);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_Init
+* Description : Initializes the I2Cx peripheral according to the specified
+* parameters in the I2C_InitStruct.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_InitStruct: pointer to a I2C_InitTypeDef structure that
+* contains the configuration information for the specified
+* I2C peripheral.
+* Output : None
+* Return : None
+******************************************************************************/
+void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct)
+{
+ u16 tmpreg = 0, freqrange = 0;
+ u16 result = 0x04;
+ u32 pclk1 = 8000000;
+ RCC_ClocksTypeDef rcc_clocks;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_MODE(I2C_InitStruct->I2C_Mode));
+ assert_param(IS_I2C_DUTY_CYCLE(I2C_InitStruct->I2C_DutyCycle));
+ assert_param(IS_I2C_OWN_ADDRESS1(I2C_InitStruct->I2C_OwnAddress1));
+ assert_param(IS_I2C_ACK_STATE(I2C_InitStruct->I2C_Ack));
+ assert_param(IS_I2C_ACKNOWLEDGE_ADDRESS(I2C_InitStruct->I2C_AcknowledgedAddress));
+ assert_param(IS_I2C_CLOCK_SPEED(I2C_InitStruct->I2C_ClockSpeed));
+
+/*---------------------------- I2Cx CR2 Configuration ------------------------*/
+ /* Get the I2Cx CR2 value */
+ tmpreg = I2Cx->CR2;
+ /* Clear frequency FREQ[5:0] bits */
+ tmpreg &= CR2_FREQ_Reset;
+ /* Get pclk1 frequency value */
+ RCC_GetClocksFreq(&rcc_clocks);
+ pclk1 = rcc_clocks.PCLK1_Frequency;
+ /* Set frequency bits depending on pclk1 value */
+ freqrange = (u16)(pclk1 / 1000000);
+ tmpreg |= freqrange;
+ /* Write to I2Cx CR2 */
+ I2Cx->CR2 = tmpreg;
+
+/*---------------------------- I2Cx CCR Configuration ------------------------*/
+ /* Disable the selected I2C peripheral to configure TRISE */
+ I2Cx->CR1 &= CR1_PE_Reset;
+
+ /* Reset tmpreg value */
+ /* Clear F/S, DUTY and CCR[11:0] bits */
+ tmpreg = 0;
+
+ /* Configure speed in standard mode */
+ if (I2C_InitStruct->I2C_ClockSpeed <= 100000)
+ {
+ /* Standard mode speed calculate */
+ result = (u16)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed << 1));
+ /* Test if CCR value is under 0x4*/
+ if (result < 0x04)
+ {
+ /* Set minimum allowed value */
+ result = 0x04;
+ }
+ /* Set speed value for standard mode */
+ tmpreg |= result;
+ /* Set Maximum Rise Time for standard mode */
+ I2Cx->TRISE = freqrange + 1;
+ }
+ /* Configure speed in fast mode */
+ else /*(I2C_InitStruct->I2C_ClockSpeed <= 400000)*/
+ {
+ if (I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_2)
+ {
+ /* Fast mode speed calculate: Tlow/Thigh = 2 */
+ result = (u16)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 3));
+ }
+ else /*I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_16_9*/
+ {
+ /* Fast mode speed calculate: Tlow/Thigh = 16/9 */
+ result = (u16)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 25));
+ /* Set DUTY bit */
+ result |= I2C_DutyCycle_16_9;
+ }
+ /* Test if CCR value is under 0x1*/
+ if ((result & CCR_CCR_Set) == 0)
+ {
+ /* Set minimum allowed value */
+ result |= (u16)0x0001;
+ }
+ /* Set speed value and set F/S bit for fast mode */
+ tmpreg |= result | CCR_FS_Set;
+ /* Set Maximum Rise Time for fast mode */
+ I2Cx->TRISE = (u16)(((freqrange * 300) / 1000) + 1);
+ }
+ /* Write to I2Cx CCR */
+ I2Cx->CCR = tmpreg;
+
+ /* Enable the selected I2C peripheral */
+ I2Cx->CR1 |= CR1_PE_Set;
+
+/*---------------------------- I2Cx CR1 Configuration ------------------------*/
+ /* Get the I2Cx CR1 value */
+ tmpreg = I2Cx->CR1;
+ /* Clear ACK, SMBTYPE and SMBUS bits */
+ tmpreg &= CR1_CLEAR_Mask;
+ /* Configure I2Cx: mode and acknowledgement */
+ /* Set SMBTYPE and SMBUS bits according to I2C_Mode value */
+ /* Set ACK bit according to I2C_Ack value */
+ tmpreg |= (u16)((u32)I2C_InitStruct->I2C_Mode | I2C_InitStruct->I2C_Ack);
+ /* Write to I2Cx CR1 */
+ I2Cx->CR1 = tmpreg;
+
+/*---------------------------- I2Cx OAR1 Configuration -----------------------*/
+ /* Set I2Cx Own Address1 and acknowledged address */
+ I2Cx->OAR1 = (I2C_InitStruct->I2C_AcknowledgedAddress | I2C_InitStruct->I2C_OwnAddress1);
+}
+
+/*******************************************************************************
+* Function Name : I2C_StructInit
+* Description : Fills each I2C_InitStruct member with its default value.
+* Input : - I2C_InitStruct: pointer to an I2C_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct)
+{
+/*---------------- Reset I2C init structure parameters values ----------------*/
+ /* Initialize the I2C_Mode member */
+ I2C_InitStruct->I2C_Mode = I2C_Mode_I2C;
+
+ /* Initialize the I2C_DutyCycle member */
+ I2C_InitStruct->I2C_DutyCycle = I2C_DutyCycle_2;
+
+ /* Initialize the I2C_OwnAddress1 member */
+ I2C_InitStruct->I2C_OwnAddress1 = 0;
+
+ /* Initialize the I2C_Ack member */
+ I2C_InitStruct->I2C_Ack = I2C_Ack_Disable;
+
+ /* Initialize the I2C_AcknowledgedAddress member */
+ I2C_InitStruct->I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
+
+ /* initialize the I2C_ClockSpeed member */
+ I2C_InitStruct->I2C_ClockSpeed = 5000;
+}
+
+/*******************************************************************************
+* Function Name : I2C_Cmd
+* Description : Enables or disables the specified I2C peripheral.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2Cx peripheral. This parameter
+* can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected I2C peripheral */
+ I2Cx->CR1 |= CR1_PE_Set;
+ }
+ else
+ {
+ /* Disable the selected I2C peripheral */
+ I2Cx->CR1 &= CR1_PE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_DMACmd
+* Description : Enables or disables the specified I2C DMA requests.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C DMA transfer.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected I2C DMA requests */
+ I2Cx->CR2 |= CR2_DMAEN_Set;
+ }
+ else
+ {
+ /* Disable the selected I2C DMA requests */
+ I2Cx->CR2 &= CR2_DMAEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_DMALastTransferCmd
+* Description : Specifies that the next DMA transfer is the last one.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C DMA last transfer.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Next DMA transfer is the last transfer */
+ I2Cx->CR2 |= CR2_LAST_Set;
+ }
+ else
+ {
+ /* Next DMA transfer is not the last transfer */
+ I2Cx->CR2 &= CR2_LAST_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_GenerateSTART
+* Description : Generates I2Cx communication START condition.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C START condition generation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None.
+*******************************************************************************/
+void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Generate a START condition */
+ I2Cx->CR1 |= CR1_START_Set;
+ }
+ else
+ {
+ /* Disable the START condition generation */
+ I2Cx->CR1 &= CR1_START_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_GenerateSTOP
+* Description : Generates I2Cx communication STOP condition.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C STOP condition generation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None.
+*******************************************************************************/
+void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Generate a STOP condition */
+ I2Cx->CR1 |= CR1_STOP_Set;
+ }
+ else
+ {
+ /* Disable the STOP condition generation */
+ I2Cx->CR1 &= CR1_STOP_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_AcknowledgeConfig
+* Description : Enables or disables the specified I2C acknowledge feature.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C Acknowledgement.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None.
+*******************************************************************************/
+void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the acknowledgement */
+ I2Cx->CR1 |= CR1_ACK_Set;
+ }
+ else
+ {
+ /* Disable the acknowledgement */
+ I2Cx->CR1 &= CR1_ACK_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_OwnAddress2Config
+* Description : Configures the specified I2C own address2.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - Address: specifies the 7bit I2C own address2.
+* Output : None
+* Return : None.
+*******************************************************************************/
+void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, u8 Address)
+{
+ u16 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+ /* Get the old register value */
+ tmpreg = I2Cx->OAR2;
+ /* Reset I2Cx Own address2 bit [7:1] */
+ tmpreg &= OAR2_ADD2_Reset;
+ /* Set I2Cx Own address2 */
+ tmpreg |= (u16)(Address & (u16)0x00FE);
+ /* Store the new register value */
+ I2Cx->OAR2 = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : I2C_DualAddressCmd
+* Description : Enables or disables the specified I2C dual addressing mode.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C dual addressing mode.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable dual addressing mode */
+ I2Cx->OAR2 |= OAR2_ENDUAL_Set;
+ }
+ else
+ {
+ /* Disable dual addressing mode */
+ I2Cx->OAR2 &= OAR2_ENDUAL_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_GeneralCallCmd
+* Description : Enables or disables the specified I2C general call feature.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C General call.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable generall call */
+ I2Cx->CR1 |= CR1_ENGC_Set;
+ }
+ else
+ {
+ /* Disable generall call */
+ I2Cx->CR1 &= CR1_ENGC_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_ITConfig
+* Description : Enables or disables the specified I2C interrupts.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_IT: specifies the I2C interrupts sources to be enabled
+* or disabled.
+* This parameter can be any combination of the following values:
+* - I2C_IT_BUF: Buffer interrupt mask
+* - I2C_IT_EVT: Event interrupt mask
+* - I2C_IT_ERR: Error interrupt mask
+* - NewState: new state of the specified I2C interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_ITConfig(I2C_TypeDef* I2Cx, u16 I2C_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+ assert_param(IS_I2C_CONFIG_IT(I2C_IT));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected I2C interrupts */
+ I2Cx->CR2 |= I2C_IT;
+ }
+ else
+ {
+ /* Disable the selected I2C interrupts */
+ I2Cx->CR2 &= (u16)~I2C_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_SendData
+* Description : Sends a data byte through the I2Cx peripheral.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - Data: Byte to be transmitted..
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_SendData(I2C_TypeDef* I2Cx, u8 Data)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+ /* Write in the DR register the data to be sent */
+ I2Cx->DR = Data;
+}
+
+/*******************************************************************************
+* Function Name : I2C_ReceiveData
+* Description : Returns the most recent received data by the I2Cx peripheral.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* Output : None
+* Return : The value of the received data.
+*******************************************************************************/
+u8 I2C_ReceiveData(I2C_TypeDef* I2Cx)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+ /* Return the data in the DR register */
+ return (u8)I2Cx->DR;
+}
+
+/*******************************************************************************
+* Function Name : I2C_Send7bitAddress
+* Description : Transmits the address byte to select the slave device.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - Address: specifies the slave address which will be transmitted
+* - I2C_Direction: specifies whether the I2C device will be a
+* Transmitter or a Receiver.
+* This parameter can be one of the following values
+* - I2C_Direction_Transmitter: Transmitter mode
+* - I2C_Direction_Receiver: Receiver mode
+* Output : None
+* Return : None.
+*******************************************************************************/
+void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, u8 Address, u8 I2C_Direction)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_DIRECTION(I2C_Direction));
+
+ /* Test on the direction to set/reset the read/write bit */
+ if (I2C_Direction != I2C_Direction_Transmitter)
+ {
+ /* Set the address bit0 for read */
+ Address |= OAR1_ADD0_Set;
+ }
+ else
+ {
+ /* Reset the address bit0 for write */
+ Address &= OAR1_ADD0_Reset;
+ }
+ /* Send the address */
+ I2Cx->DR = Address;
+}
+
+/*******************************************************************************
+* Function Name : I2C_ReadRegister
+* Description : Reads the specified I2C register and returns its value.
+* Input1 : - I2C_Register: specifies the register to read.
+* This parameter can be one of the following values:
+* - I2C_Register_CR1: CR1 register.
+* - I2C_Register_CR2: CR2 register.
+* - I2C_Register_OAR1: OAR1 register.
+* - I2C_Register_OAR2: OAR2 register.
+* - I2C_Register_DR: DR register.
+* - I2C_Register_SR1: SR1 register.
+* - I2C_Register_SR2: SR2 register.
+* - I2C_Register_CCR: CCR register.
+* - I2C_Register_TRISE: TRISE register.
+* Output : None
+* Return : The value of the read register.
+*******************************************************************************/
+u16 I2C_ReadRegister(I2C_TypeDef* I2Cx, u8 I2C_Register)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_REGISTER(I2C_Register));
+
+ /* Return the selected register value */
+ return (*(vu16 *)(*((vu32 *)&I2Cx) + I2C_Register));
+}
+
+/*******************************************************************************
+* Function Name : I2C_SoftwareResetCmd
+* Description : Enables or disables the specified I2C software reset.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C software reset.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Peripheral under reset */
+ I2Cx->CR1 |= CR1_SWRST_Set;
+ }
+ else
+ {
+ /* Peripheral not under reset */
+ I2Cx->CR1 &= CR1_SWRST_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_SMBusAlertConfig
+* Description : Drives the SMBusAlert pin high or low for the specified I2C.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_SMBusAlert: specifies SMBAlert pin level.
+* This parameter can be one of the following values:
+* - I2C_SMBusAlert_Low: SMBAlert pin driven low
+* - I2C_SMBusAlert_High: SMBAlert pin driven high
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, u16 I2C_SMBusAlert)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_SMBUS_ALERT(I2C_SMBusAlert));
+
+ if (I2C_SMBusAlert == I2C_SMBusAlert_Low)
+ {
+ /* Drive the SMBusAlert pin Low */
+ I2Cx->CR1 |= I2C_SMBusAlert_Low;
+ }
+ else
+ {
+ /* Drive the SMBusAlert pin High */
+ I2Cx->CR1 &= I2C_SMBusAlert_High;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_TransmitPEC
+* Description : Enables or disables the specified I2C PEC transfer.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2C PEC transmission.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected I2C PEC transmission */
+ I2Cx->CR1 |= CR1_PEC_Set;
+ }
+ else
+ {
+ /* Disable the selected I2C PEC transmission */
+ I2Cx->CR1 &= CR1_PEC_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_PECPositionConfig
+* Description : Selects the specified I2C PEC position.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_PECPosition: specifies the PEC position.
+* This parameter can be one of the following values:
+* - I2C_PECPosition_Next: indicates that the next
+* byte is PEC
+* - I2C_PECPosition_Current: indicates that current
+* byte is PEC
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, u16 I2C_PECPosition)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_PEC_POSITION(I2C_PECPosition));
+
+ if (I2C_PECPosition == I2C_PECPosition_Next)
+ {
+ /* Next byte in shift register is PEC */
+ I2Cx->CR1 |= I2C_PECPosition_Next;
+ }
+ else
+ {
+ /* Current byte in shift register is PEC */
+ I2Cx->CR1 &= I2C_PECPosition_Current;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_CalculatePEC
+* Description : Enables or disables the PEC value calculation of the
+* transfered bytes.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2Cx PEC value calculation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected I2C PEC calculation */
+ I2Cx->CR1 |= CR1_ENPEC_Set;
+ }
+ else
+ {
+ /* Disable the selected I2C PEC calculation */
+ I2Cx->CR1 &= CR1_ENPEC_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_GetPEC
+* Description : Returns the PEC value for the specified I2C.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* Output : None
+* Return : The PEC value.
+*******************************************************************************/
+u8 I2C_GetPEC(I2C_TypeDef* I2Cx)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+ /* Return the selected I2C PEC value */
+ return ((I2Cx->SR2) >> 8);
+}
+
+/*******************************************************************************
+* Function Name : I2C_ARPCmd
+* Description : Enables or disables the specified I2C ARP.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2Cx ARP.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected I2C ARP */
+ I2Cx->CR1 |= CR1_ENARP_Set;
+ }
+ else
+ {
+ /* Disable the selected I2C ARP */
+ I2Cx->CR1 &= CR1_ENARP_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_StretchClockCmd
+* Description : Enables or disables the specified I2C Clock stretching.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - NewState: new state of the I2Cx Clock stretching.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState == DISABLE)
+ {
+ /* Enable the selected I2C Clock stretching */
+ I2Cx->CR1 |= CR1_NOSTRETCH_Set;
+ }
+ else
+ {
+ /* Disable the selected I2C Clock stretching */
+ I2Cx->CR1 &= CR1_NOSTRETCH_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_FastModeDutyCycleConfig
+* Description : Selects the specified I2C fast mode duty cycle.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_DutyCycle: specifies the fast mode duty cycle.
+* This parameter can be one of the following values:
+* - I2C_DutyCycle_2: I2C fast mode Tlow/Thigh = 2
+* - I2C_DutyCycle_16_9: I2C fast mode Tlow/Thigh = 16/9
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, u16 I2C_DutyCycle)
+{
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_DUTY_CYCLE(I2C_DutyCycle));
+
+ if (I2C_DutyCycle != I2C_DutyCycle_16_9)
+ {
+ /* I2C fast mode Tlow/Thigh=2 */
+ I2Cx->CCR &= I2C_DutyCycle_2;
+ }
+ else
+ {
+ /* I2C fast mode Tlow/Thigh=16/9 */
+ I2Cx->CCR |= I2C_DutyCycle_16_9;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2C_GetLastEvent
+* Description : Returns the last I2Cx Event.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* Output : None
+* Return : The last event
+*******************************************************************************/
+u32 I2C_GetLastEvent(I2C_TypeDef* I2Cx)
+{
+ u32 lastevent = 0;
+ u32 flag1 = 0, flag2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+ /* Read the I2Cx status register */
+ flag1 = I2Cx->SR1;
+ flag2 = I2Cx->SR2;
+ flag2 = flag2 << 16;
+
+ /* Get the last event value from I2C status register */
+ lastevent = (flag1 | flag2) & FLAG_Mask;
+
+ /* Return status */
+ return lastevent;
+}
+
+/*******************************************************************************
+* Function Name : I2C_CheckEvent
+* Description : Checks whether the last I2Cx Event is equal to the one passed
+* as parameter.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_EVENT: specifies the event to be checked.
+* This parameter can be one of the following values:
+* - I2C_EVENT_SLAVE_ADDRESS_MATCHED : EV1
+* - I2C_EVENT_SLAVE_BYTE_RECEIVED : EV2
+* - I2C_EVENT_SLAVE_BYTE_TRANSMITTED : EV3
+* - I2C_EVENT_SLAVE_ACK_FAILURE : EV3-2
+* - I2C_EVENT_MASTER_MODE_SELECT : EV5
+* - I2C_EVENT_MASTER_MODE_SELECTED : EV6
+* - I2C_EVENT_MASTER_BYTE_RECEIVED : EV7
+* - I2C_EVENT_MASTER_BYTE_TRANSMITTED : EV8
+* - I2C_EVENT_MASTER_MODE_ADDRESS10 : EV9
+* - I2C_EVENT_SLAVE_STOP_DETECTED : EV4
+* Output : None
+* Return : An ErrorStatus enumuration value:
+* - SUCCESS: Last event is equal to the I2C_EVENT
+* - ERROR: Last event is different from the I2C_EVENT
+*******************************************************************************/
+ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, u32 I2C_EVENT)
+{
+ u32 lastevent = 0;
+ u32 flag1 = 0, flag2 = 0;
+ ErrorStatus status = ERROR;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_EVENT(I2C_EVENT));
+
+ /* Read the I2Cx status register */
+ flag1 = I2Cx->SR1;
+ flag2 = I2Cx->SR2;
+ flag2 = flag2 << 16;
+
+ /* Get the last event value from I2C status register */
+ lastevent = (flag1 | flag2) & FLAG_Mask;
+
+ /* Check whether the last event is equal to I2C_EVENT */
+ if (lastevent == I2C_EVENT )
+ {
+ /* SUCCESS: last event is equal to I2C_EVENT */
+ status = SUCCESS;
+ }
+ else
+ {
+ /* ERROR: last event is different from I2C_EVENT */
+ status = ERROR;
+ }
+
+ /* Return status */
+ return status;
+}
+
+/*******************************************************************************
+* Function Name : I2C_GetFlagStatus
+* Description : Checks whether the specified I2C flag is set or not.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - I2C_FLAG_DUALF: Dual flag (Slave mode)
+* - I2C_FLAG_SMBHOST: SMBus host header (Slave mode)
+* - I2C_FLAG_SMBDEFAULT: SMBus default header (Slave mode)
+* - I2C_FLAG_GENCALL: General call header flag (Slave mode)
+* - I2C_FLAG_TRA: Transmitter/Receiver flag
+* - I2C_FLAG_BUSY: Bus busy flag
+* - I2C_FLAG_MSL: Master/Slave flag
+* - I2C_FLAG_SMBALERT: SMBus Alert flag
+* - I2C_FLAG_TIMEOUT: Timeout or Tlow error flag
+* - I2C_FLAG_PECERR: PEC error in reception flag
+* - I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode)
+* - I2C_FLAG_AF: Acknowledge failure flag
+* - I2C_FLAG_ARLO: Arbitration lost flag (Master mode)
+* - I2C_FLAG_BERR: Bus error flag
+* - I2C_FLAG_TXE: Data register empty flag (Transmitter)
+* - I2C_FLAG_RXNE: Data register not empty (Receiver) flag
+* - I2C_FLAG_STOPF: Stop detection flag (Slave mode)
+* - I2C_FLAG_ADD10: 10-bit header sent flag (Master mode)
+* - I2C_FLAG_BTF: Byte transfer finished flag
+* - I2C_FLAG_ADDR: Address sent flag (Master mode) “ADSL”
+* Address matched flag (Slave mode)”ENDAD”
+* - I2C_FLAG_SB: Start bit flag (Master mode)
+* Output : None
+* Return : The new state of I2C_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, u32 I2C_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+ u32 i2creg = 0, i2cxbase = 0;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_GET_FLAG(I2C_FLAG));
+
+ /* Get the I2Cx peripheral base address */
+ i2cxbase = (*(u32*)&(I2Cx));
+
+ /* Read flag register index */
+ i2creg = I2C_FLAG >> 28;
+
+ /* Get bit[23:0] of the flag */
+ I2C_FLAG &= FLAG_Mask;
+
+ if(i2creg != 0)
+ {
+ /* Get the I2Cx SR1 register address */
+ i2cxbase += 0x14;
+ }
+ else
+ {
+ /* Flag in I2Cx SR2 Register */
+ I2C_FLAG = (u32)(I2C_FLAG >> 16);
+ /* Get the I2Cx SR2 register address */
+ i2cxbase += 0x18;
+ }
+
+ if(((*(vu32 *)i2cxbase) & I2C_FLAG) != (u32)RESET)
+ {
+ /* I2C_FLAG is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* I2C_FLAG is reset */
+ bitstatus = RESET;
+ }
+
+ /* Return the I2C_FLAG status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : I2C_ClearFlag
+* Description : Clears the I2Cx's pending flags.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_FLAG: specifies the flag to clear.
+* This parameter can be any combination of the following
+* values:
+* - I2C_FLAG_SMBALERT: SMBus Alert flag
+* - I2C_FLAG_TIMEOUT: Timeout or Tlow error flag
+* - I2C_FLAG_PECERR: PEC error in reception flag
+* - I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode)
+* - I2C_FLAG_AF: Acknowledge failure flag
+* - I2C_FLAG_ARLO: Arbitration lost flag (Master mode)
+* - I2C_FLAG_BERR: Bus error flag
+*
+* Notes:
+* - STOPF (STOP detection) is cleared by software
+* sequence: a read operation to I2C_SR1 register
+* (I2C_GetFlagStatus()) followed by a write operation
+* to I2C_CR1 register (I2C_Cmd() to re-enable the
+* I2C peripheral).
+* - ADD10 (10-bit header sent) is cleared by software
+* sequence: a read operation to I2C_SR1
+* (I2C_GetFlagStatus()) followed by writing the
+* second byte of the address in DR register.
+* - BTF (Byte Transfer Finished) is cleared by software
+* sequence: a read operation to I2C_SR1 register
+* (I2C_GetFlagStatus()) followed by a read/write to
+* I2C_DR register (I2C_SendData()).
+* - ADDR (Address sent) is cleared by software sequence:
+* a read operation to I2C_SR1 register
+* (I2C_GetFlagStatus()) followed by a read operation to
+* I2C_SR2 register ((void)(I2Cx->SR2)).
+* - SB (Start Bit) is cleared software sequence: a read
+* operation to I2C_SR1 register (I2C_GetFlagStatus())
+* followed by a write operation to I2C_DR reigister
+* (I2C_SendData()).
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_ClearFlag(I2C_TypeDef* I2Cx, u32 I2C_FLAG)
+{
+ u32 flagpos = 0;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_CLEAR_FLAG(I2C_FLAG));
+
+ /* Get the I2C flag position */
+ flagpos = I2C_FLAG & FLAG_Mask;
+
+ /* Clear the selected I2C flag */
+ I2Cx->SR1 = (u16)~flagpos;
+}
+
+/*******************************************************************************
+* Function Name : I2C_GetITStatus
+* Description : Checks whether the specified I2C interrupt has occurred or not.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_IT: specifies the interrupt source to check.
+* This parameter can be one of the following values:
+* - I2C_IT_SMBALERT: SMBus Alert flag
+* - I2C_IT_TIMEOUT: Timeout or Tlow error flag
+* - I2C_IT_PECERR: PEC error in reception flag
+* - I2C_IT_OVR: Overrun/Underrun flag (Slave mode)
+* - I2C_IT_AF: Acknowledge failure flag
+* - I2C_IT_ARLO: Arbitration lost flag (Master mode)
+* - I2C_IT_BERR: Bus error flag
+* - I2C_IT_TXE: Data register empty flag (Transmitter)
+* - I2C_IT_RXNE: Data register not empty (Receiver) flag
+* - I2C_IT_STOPF: Stop detection flag (Slave mode)
+* - I2C_IT_ADD10: 10-bit header sent flag (Master mode)
+* - I2C_IT_BTF: Byte transfer finished flag
+* - I2C_IT_ADDR: Address sent flag (Master mode) “ADSL”
+* Address matched flag (Slave mode)”ENDAD”
+* - I2C_IT_SB: Start bit flag (Master mode)
+* Output : None
+* Return : The new state of I2C_IT (SET or RESET).
+*******************************************************************************/
+ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, u32 I2C_IT)
+{
+ ITStatus bitstatus = RESET;
+ u32 enablestatus = 0;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_GET_IT(I2C_IT));
+
+ /* Check if the interrupt source is enabled or not */
+ enablestatus = (u32)(((I2C_IT & ITEN_Mask) >> 16) & (I2Cx->CR2)) ;
+
+ /* Get bit[23:0] of the flag */
+ I2C_IT &= FLAG_Mask;
+
+ /* Check the status of the specified I2C flag */
+ if (((I2Cx->SR1 & I2C_IT) != (u32)RESET) && enablestatus)
+ {
+ /* I2C_IT is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* I2C_IT is reset */
+ bitstatus = RESET;
+ }
+ /* Return the I2C_IT status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : I2C_ClearITPendingBit
+* Description : Clears the I2Cx’s interrupt pending bits.
+* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+* - I2C_IT: specifies the interrupt pending bit to clear.
+* This parameter can be any combination of the following
+* values:
+* - I2C_IT_SMBALERT: SMBus Alert interrupt
+* - I2C_IT_TIMEOUT: Timeout or Tlow error interrupt
+* - I2C_IT_PECERR: PEC error in reception interrupt
+* - I2C_IT_OVR: Overrun/Underrun interrupt (Slave mode)
+* - I2C_IT_AF: Acknowledge failure interrupt
+* - I2C_IT_ARLO: Arbitration lost interrupt (Master mode)
+* - I2C_IT_BERR: Bus error interrupt
+*
+* Notes:
+* - STOPF (STOP detection) is cleared by software
+* sequence: a read operation to I2C_SR1 register
+* (I2C_GetITStatus()) followed by a write operation to
+* I2C_CR1 register (I2C_Cmd() to re-enable the I2C
+* peripheral).
+* - ADD10 (10-bit header sent) is cleared by software
+* sequence: a read operation to I2C_SR1
+* (I2C_GetITStatus()) followed by writing the second
+* byte of the address in I2C_DR register.
+* - BTF (Byte Transfer Finished) is cleared by software
+* sequence: a read operation to I2C_SR1 register
+* (I2C_GetITStatus()) followed by a read/write to
+* I2C_DR register (I2C_SendData()).
+* - ADDR (Address sent) is cleared by software sequence:
+* a read operation to I2C_SR1 register (I2C_GetITStatus())
+* followed by a read operation to I2C_SR2 register
+* ((void)(I2Cx->SR2)).
+* - SB (Start Bit) is cleared by software sequence: a
+* read operation to I2C_SR1 register (I2C_GetITStatus())
+* followed by a write operation to I2C_DR reigister
+* (I2C_SendData()).
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, u32 I2C_IT)
+{
+ u32 flagpos = 0;
+
+ /* Check the parameters */
+ assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+ assert_param(IS_I2C_CLEAR_IT(I2C_IT));
+
+ /* Get the I2C flag position */
+ flagpos = I2C_IT & FLAG_Mask;
+
+ /* Clear the selected I2C flag */
+ I2Cx->SR1 = (u16)~flagpos;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_iwdg.c b/src/stm32lib/src/stm32f10x_iwdg.c new file mode 100644 index 0000000..77cb094 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_iwdg.c @@ -0,0 +1,148 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_iwdg.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the IWDG firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_iwdg.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ---------------------- IWDG registers bit mask ------------------------ */
+/* KR register bit mask */
+#define KR_KEY_Reload ((u16)0xAAAA)
+#define KR_KEY_Enable ((u16)0xCCCC)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : IWDG_WriteAccessCmd
+* Description : Enables or disables write access to IWDG_PR and IWDG_RLR
+* registers.
+* Input : - IWDG_WriteAccess: new state of write access to IWDG_PR and
+* IWDG_RLR registers.
+* This parameter can be one of the following values:
+* - IWDG_WriteAccess_Enable: Enable write access to
+* IWDG_PR and IWDG_RLR registers
+* - IWDG_WriteAccess_Disable: Disable write access to
+* IWDG_PR and IWDG_RLR registers
+* Output : None
+* Return : None
+*******************************************************************************/
+void IWDG_WriteAccessCmd(u16 IWDG_WriteAccess)
+{
+ /* Check the parameters */
+ assert_param(IS_IWDG_WRITE_ACCESS(IWDG_WriteAccess));
+
+ IWDG->KR = IWDG_WriteAccess;
+}
+
+/*******************************************************************************
+* Function Name : IWDG_SetPrescaler
+* Description : Sets IWDG Prescaler value.
+* Input : - IWDG_Prescaler: specifies the IWDG Prescaler value.
+* This parameter can be one of the following values:
+* - IWDG_Prescaler_4: IWDG prescaler set to 4
+* - IWDG_Prescaler_8: IWDG prescaler set to 8
+* - IWDG_Prescaler_16: IWDG prescaler set to 16
+* - IWDG_Prescaler_32: IWDG prescaler set to 32
+* - IWDG_Prescaler_64: IWDG prescaler set to 64
+* - IWDG_Prescaler_128: IWDG prescaler set to 128
+* - IWDG_Prescaler_256: IWDG prescaler set to 256
+* Output : None
+* Return : None
+*******************************************************************************/
+void IWDG_SetPrescaler(u8 IWDG_Prescaler)
+{
+ /* Check the parameters */
+ assert_param(IS_IWDG_PRESCALER(IWDG_Prescaler));
+
+ IWDG->PR = IWDG_Prescaler;
+}
+
+/*******************************************************************************
+* Function Name : IWDG_SetReload
+* Description : Sets IWDG Reload value.
+* Input : - Reload: specifies the IWDG Reload value.
+* This parameter must be a number between 0 and 0x0FFF.
+* Output : None
+* Return : None
+*******************************************************************************/
+void IWDG_SetReload(u16 Reload)
+{
+ /* Check the parameters */
+ assert_param(IS_IWDG_RELOAD(Reload));
+
+ IWDG->RLR = Reload;
+}
+
+/*******************************************************************************
+* Function Name : IWDG_ReloadCounter
+* Description : Reloads IWDG counter with value defined in the reload register
+* (write access to IWDG_PR and IWDG_RLR registers disabled).
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void IWDG_ReloadCounter(void)
+{
+ IWDG->KR = KR_KEY_Reload;
+}
+
+/*******************************************************************************
+* Function Name : IWDG_Enable
+* Description : Enables IWDG (write access to IWDG_PR and IWDG_RLR registers
+* disabled).
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void IWDG_Enable(void)
+{
+ IWDG->KR = KR_KEY_Enable;
+}
+
+/*******************************************************************************
+* Function Name : IWDG_GetFlagStatus
+* Description : Checks whether the specified IWDG flag is set or not.
+* Input : - IWDG_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - IWDG_FLAG_PVU: Prescaler Value Update on going
+* - IWDG_FLAG_RVU: Reload Value Update on going
+* Output : None
+* Return : The new state of IWDG_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus IWDG_GetFlagStatus(u16 IWDG_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_IWDG_FLAG(IWDG_FLAG));
+
+ if ((IWDG->SR & IWDG_FLAG) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+
+ /* Return the flag status */
+ return bitstatus;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_lib.c b/src/stm32lib/src/stm32f10x_lib.c new file mode 100644 index 0000000..21d5ce5 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_lib.c @@ -0,0 +1,303 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_lib.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all peripherals pointers initialization.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+#define EXT
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_lib.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+#ifdef DEBUG
+/*******************************************************************************
+* Function Name : debug
+* Description : This function initialize peripherals pointers.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void debug(void)
+{
+
+/************************************* ADC ************************************/
+#ifdef _ADC1
+ ADC1 = (ADC_TypeDef *) ADC1_BASE;
+#endif /*_ADC1 */
+
+#ifdef _ADC2
+ ADC2 = (ADC_TypeDef *) ADC2_BASE;
+#endif /*_ADC2 */
+
+#ifdef _ADC3
+ ADC3 = (ADC_TypeDef *) ADC3_BASE;
+#endif /*_ADC3 */
+
+/************************************* BKP ************************************/
+#ifdef _BKP
+ BKP = (BKP_TypeDef *) BKP_BASE;
+#endif /*_BKP */
+
+/************************************* CAN ************************************/
+#ifdef _CAN
+ CAN = (CAN_TypeDef *) CAN_BASE;
+#endif /*_CAN */
+
+/************************************* CRC ************************************/
+#ifdef _CRC
+ CRC = (CRC_TypeDef *) CRC_BASE;
+#endif /*_CRC */
+
+/************************************* DAC ************************************/
+#ifdef _DAC
+ DAC = (DAC_TypeDef *) DAC_BASE;
+#endif /*_DAC */
+
+/************************************* DBGMCU**********************************/
+#ifdef _DBGMCU
+ DBGMCU = (DBGMCU_TypeDef *) DBGMCU_BASE;
+#endif /*_DBGMCU */
+
+/************************************* DMA ************************************/
+#ifdef _DMA
+ DMA1 = (DMA_TypeDef *) DMA1_BASE;
+ DMA2 = (DMA_TypeDef *) DMA2_BASE;
+#endif /*_DMA */
+
+#ifdef _DMA1_Channel1
+ DMA1_Channel1 = (DMA_Channel_TypeDef *) DMA1_Channel1_BASE;
+#endif /*_DMA1_Channel1 */
+
+#ifdef _DMA1_Channel2
+ DMA1_Channel2 = (DMA_Channel_TypeDef *) DMA1_Channel2_BASE;
+#endif /*_DMA1_Channel2 */
+
+#ifdef _DMA1_Channel3
+ DMA1_Channel3 = (DMA_Channel_TypeDef *) DMA1_Channel3_BASE;
+#endif /*_DMA1_Channel3 */
+
+#ifdef _DMA1_Channel4
+ DMA1_Channel4 = (DMA_Channel_TypeDef *) DMA1_Channel4_BASE;
+#endif /*_DMA1_Channel4 */
+
+#ifdef _DMA1_Channel5
+ DMA1_Channel5 = (DMA_Channel_TypeDef *) DMA1_Channel5_BASE;
+#endif /*_DMA1_Channel5 */
+
+#ifdef _DMA1_Channel6
+ DMA1_Channel6 = (DMA_Channel_TypeDef *) DMA1_Channel6_BASE;
+#endif /*_DMA1_Channel6 */
+
+#ifdef _DMA1_Channel7
+ DMA1_Channel7 = (DMA_Channel_TypeDef *) DMA1_Channel7_BASE;
+#endif /*_DMA1_Channel7 */
+
+#ifdef _DMA2_Channel1
+ DMA2_Channel1 = (DMA_Channel_TypeDef *) DMA2_Channel1_BASE;
+#endif /*_DMA2_Channel1 */
+
+#ifdef _DMA2_Channel2
+ DMA2_Channel2 = (DMA_Channel_TypeDef *) DMA2_Channel2_BASE;
+#endif /*_DMA2_Channel2 */
+
+#ifdef _DMA2_Channel3
+ DMA2_Channel3 = (DMA_Channel_TypeDef *) DMA2_Channel3_BASE;
+#endif /*_DMA2_Channel3 */
+
+#ifdef _DMA2_Channel4
+ DMA2_Channel4 = (DMA_Channel_TypeDef *) DMA2_Channel4_BASE;
+#endif /*_DMA2_Channel4 */
+
+#ifdef _DMA2_Channel5
+ DMA2_Channel5 = (DMA_Channel_TypeDef *) DMA2_Channel5_BASE;
+#endif /*_DMA2_Channel5 */
+
+/************************************* EXTI ***********************************/
+#ifdef _EXTI
+ EXTI = (EXTI_TypeDef *) EXTI_BASE;
+#endif /*_EXTI */
+
+/************************************* FLASH and Option Bytes *****************/
+#ifdef _FLASH
+ FLASH = (FLASH_TypeDef *) FLASH_R_BASE;
+ OB = (OB_TypeDef *) OB_BASE;
+#endif /*_FLASH */
+
+/************************************* FSMC ***********************************/
+#ifdef _FSMC
+ FSMC_Bank1 = (FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE;
+ FSMC_Bank1E = (FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE;
+ FSMC_Bank2 = (FSMC_Bank2_TypeDef *) FSMC_Bank2_R_BASE;
+ FSMC_Bank3 = (FSMC_Bank3_TypeDef *) FSMC_Bank3_R_BASE;
+ FSMC_Bank4 = (FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE;
+#endif /*_FSMC */
+
+/************************************* GPIO ***********************************/
+#ifdef _GPIOA
+ GPIOA = (GPIO_TypeDef *) GPIOA_BASE;
+#endif /*_GPIOA */
+
+#ifdef _GPIOB
+ GPIOB = (GPIO_TypeDef *) GPIOB_BASE;
+#endif /*_GPIOB */
+
+#ifdef _GPIOC
+ GPIOC = (GPIO_TypeDef *) GPIOC_BASE;
+#endif /*_GPIOC */
+
+#ifdef _GPIOD
+ GPIOD = (GPIO_TypeDef *) GPIOD_BASE;
+#endif /*_GPIOD */
+
+#ifdef _GPIOE
+ GPIOE = (GPIO_TypeDef *) GPIOE_BASE;
+#endif /*_GPIOE */
+
+#ifdef _GPIOF
+ GPIOF = (GPIO_TypeDef *) GPIOF_BASE;
+#endif /*_GPIOF */
+
+#ifdef _GPIOG
+ GPIOG = (GPIO_TypeDef *) GPIOG_BASE;
+#endif /*_GPIOG */
+
+#ifdef _AFIO
+ AFIO = (AFIO_TypeDef *) AFIO_BASE;
+#endif /*_AFIO */
+
+/************************************* I2C ************************************/
+#ifdef _I2C1
+ I2C1 = (I2C_TypeDef *) I2C1_BASE;
+#endif /*_I2C1 */
+
+#ifdef _I2C2
+ I2C2 = (I2C_TypeDef *) I2C2_BASE;
+#endif /*_I2C2 */
+
+/************************************* IWDG ***********************************/
+#ifdef _IWDG
+ IWDG = (IWDG_TypeDef *) IWDG_BASE;
+#endif /*_IWDG */
+
+/************************************* NVIC ***********************************/
+#ifdef _NVIC
+ NVIC = (NVIC_TypeDef *) NVIC_BASE;
+ SCB = (SCB_TypeDef *) SCB_BASE;
+#endif /*_NVIC */
+
+/************************************* PWR ************************************/
+#ifdef _PWR
+ PWR = (PWR_TypeDef *) PWR_BASE;
+#endif /*_PWR */
+
+/************************************* RCC ************************************/
+#ifdef _RCC
+ RCC = (RCC_TypeDef *) RCC_BASE;
+#endif /*_RCC */
+
+/************************************* RTC ************************************/
+#ifdef _RTC
+ RTC = (RTC_TypeDef *) RTC_BASE;
+#endif /*_RTC */
+
+/************************************* SDIO ***********************************/
+#ifdef _SDIO
+ SDIO = (SDIO_TypeDef *) SDIO_BASE;
+#endif /*_SDIO */
+
+/************************************* SPI ************************************/
+#ifdef _SPI1
+ SPI1 = (SPI_TypeDef *) SPI1_BASE;
+#endif /*_SPI1 */
+
+#ifdef _SPI2
+ SPI2 = (SPI_TypeDef *) SPI2_BASE;
+#endif /*_SPI2 */
+
+#ifdef _SPI3
+ SPI3 = (SPI_TypeDef *) SPI3_BASE;
+#endif /*_SPI3 */
+
+/************************************* SysTick ********************************/
+#ifdef _SysTick
+ SysTick = (SysTick_TypeDef *) SysTick_BASE;
+#endif /*_SysTick */
+
+/************************************* TIM ************************************/
+#ifdef _TIM1
+ TIM1 = (TIM_TypeDef *) TIM1_BASE;
+#endif /*_TIM1 */
+
+#ifdef _TIM2
+ TIM2 = (TIM_TypeDef *) TIM2_BASE;
+#endif /*_TIM2 */
+
+#ifdef _TIM3
+ TIM3 = (TIM_TypeDef *) TIM3_BASE;
+#endif /*_TIM3 */
+
+#ifdef _TIM4
+ TIM4 = (TIM_TypeDef *) TIM4_BASE;
+#endif /*_TIM4 */
+
+#ifdef _TIM5
+ TIM5 = (TIM_TypeDef *) TIM5_BASE;
+#endif /*_TIM5 */
+
+#ifdef _TIM6
+ TIM6 = (TIM_TypeDef *) TIM6_BASE;
+#endif /*_TIM6 */
+
+#ifdef _TIM7
+ TIM7 = (TIM_TypeDef *) TIM7_BASE;
+#endif /*_TIM7 */
+
+#ifdef _TIM8
+ TIM8 = (TIM_TypeDef *) TIM8_BASE;
+#endif /*_TIM8 */
+
+/************************************* USART **********************************/
+#ifdef _USART1
+ USART1 = (USART_TypeDef *) USART1_BASE;
+#endif /*_USART1 */
+
+#ifdef _USART2
+ USART2 = (USART_TypeDef *) USART2_BASE;
+#endif /*_USART2 */
+
+#ifdef _USART3
+ USART3 = (USART_TypeDef *) USART3_BASE;
+#endif /*_USART3 */
+
+#ifdef _UART4
+ UART4 = (USART_TypeDef *) UART4_BASE;
+#endif /*_UART4 */
+
+#ifdef _UART5
+ UART5 = (USART_TypeDef *) UART5_BASE;
+#endif /*_UART5 */
+
+/************************************* WWDG ***********************************/
+#ifdef _WWDG
+ WWDG = (WWDG_TypeDef *) WWDG_BASE;
+#endif /*_WWDG */
+}
+#endif /* DEBUG*/
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_nvic.c b/src/stm32lib/src/stm32f10x_nvic.c new file mode 100644 index 0000000..0ce30af --- /dev/null +++ b/src/stm32lib/src/stm32f10x_nvic.c @@ -0,0 +1,751 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_nvic.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the NVIC firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_nvic.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define AIRCR_VECTKEY_MASK ((u32)0x05FA0000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : NVIC_DeInit
+* Description : Deinitializes the NVIC peripheral registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_DeInit(void)
+{
+ u32 index = 0;
+
+ NVIC->ICER[0] = 0xFFFFFFFF;
+ NVIC->ICER[1] = 0x0FFFFFFF;
+ NVIC->ICPR[0] = 0xFFFFFFFF;
+ NVIC->ICPR[1] = 0x0FFFFFFF;
+
+ for(index = 0; index < 0x0F; index++)
+ {
+ NVIC->IPR[index] = 0x00000000;
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SCBDeInit
+* Description : Deinitializes the SCB peripheral registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SCBDeInit(void)
+{
+ u32 index = 0x00;
+
+ SCB->ICSR = 0x0A000000;
+ SCB->VTOR = 0x00000000;
+ SCB->AIRCR = AIRCR_VECTKEY_MASK;
+ SCB->SCR = 0x00000000;
+ SCB->CCR = 0x00000000;
+ for(index = 0; index < 0x03; index++)
+ {
+ SCB->SHPR[index] = 0;
+ }
+ SCB->SHCSR = 0x00000000;
+ SCB->CFSR = 0xFFFFFFFF;
+ SCB->HFSR = 0xFFFFFFFF;
+ SCB->DFSR = 0xFFFFFFFF;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_PriorityGroupConfig
+* Description : Configures the priority grouping: pre-emption priority
+* and subpriority.
+* Input : - NVIC_PriorityGroup: specifies the priority grouping bits
+* length. This parameter can be one of the following values:
+* - NVIC_PriorityGroup_0: 0 bits for pre-emption priority
+* 4 bits for subpriority
+* - NVIC_PriorityGroup_1: 1 bits for pre-emption priority
+* 3 bits for subpriority
+* - NVIC_PriorityGroup_2: 2 bits for pre-emption priority
+* 2 bits for subpriority
+* - NVIC_PriorityGroup_3: 3 bits for pre-emption priority
+* 1 bits for subpriority
+* - NVIC_PriorityGroup_4: 4 bits for pre-emption priority
+* 0 bits for subpriority
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_PriorityGroupConfig(u32 NVIC_PriorityGroup)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_PRIORITY_GROUP(NVIC_PriorityGroup));
+
+ /* Set the PRIGROUP[10:8] bits according to NVIC_PriorityGroup value */
+ SCB->AIRCR = AIRCR_VECTKEY_MASK | NVIC_PriorityGroup;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_Init
+* Description : Initializes the NVIC peripheral according to the specified
+* parameters in the NVIC_InitStruct.
+* Input : - NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure
+* that contains the configuration information for the
+* specified NVIC peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct)
+{
+ u32 tmppriority = 0x00, tmpreg = 0x00, tmpmask = 0x00;
+ u32 tmppre = 0, tmpsub = 0x0F;
+
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NVIC_InitStruct->NVIC_IRQChannelCmd));
+ assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_InitStruct->NVIC_IRQChannel));
+ assert_param(IS_NVIC_PREEMPTION_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority));
+ assert_param(IS_NVIC_SUB_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelSubPriority));
+
+ if (NVIC_InitStruct->NVIC_IRQChannelCmd != DISABLE)
+ {
+ /* Compute the Corresponding IRQ Priority --------------------------------*/
+ tmppriority = (0x700 - (SCB->AIRCR & (u32)0x700))>> 0x08;
+ tmppre = (0x4 - tmppriority);
+ tmpsub = tmpsub >> tmppriority;
+
+ tmppriority = (u32)NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority << tmppre;
+ tmppriority |= NVIC_InitStruct->NVIC_IRQChannelSubPriority & tmpsub;
+
+ tmppriority = tmppriority << 0x04;
+ tmppriority = ((u32)tmppriority) << ((NVIC_InitStruct->NVIC_IRQChannel & (u8)0x03) * 0x08);
+
+ tmpreg = NVIC->IPR[(NVIC_InitStruct->NVIC_IRQChannel >> 0x02)];
+ tmpmask = (u32)0xFF << ((NVIC_InitStruct->NVIC_IRQChannel & (u8)0x03) * 0x08);
+ tmpreg &= ~tmpmask;
+ tmppriority &= tmpmask;
+ tmpreg |= tmppriority;
+
+ NVIC->IPR[(NVIC_InitStruct->NVIC_IRQChannel >> 0x02)] = tmpreg;
+
+ /* Enable the Selected IRQ Channels --------------------------------------*/
+ NVIC->ISER[(NVIC_InitStruct->NVIC_IRQChannel >> 0x05)] =
+ (u32)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (u8)0x1F);
+ }
+ else
+ {
+ /* Disable the Selected IRQ Channels -------------------------------------*/
+ NVIC->ICER[(NVIC_InitStruct->NVIC_IRQChannel >> 0x05)] =
+ (u32)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (u8)0x1F);
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_StructInit
+* Description : Fills each NVIC_InitStruct member with its default value.
+* Input : - NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure which
+* will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_StructInit(NVIC_InitTypeDef* NVIC_InitStruct)
+{
+ /* NVIC_InitStruct members default value */
+ NVIC_InitStruct->NVIC_IRQChannel = 0x00;
+ NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority = 0x00;
+ NVIC_InitStruct->NVIC_IRQChannelSubPriority = 0x00;
+ NVIC_InitStruct->NVIC_IRQChannelCmd = DISABLE;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SETPRIMASK
+* Description : Enables the PRIMASK priority: Raises the execution priority to 0.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SETPRIMASK(void)
+{
+ __SETPRIMASK();
+}
+
+/*******************************************************************************
+* Function Name : NVIC_RESETPRIMASK
+* Description : Disables the PRIMASK priority.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_RESETPRIMASK(void)
+{
+ __RESETPRIMASK();
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SETFAULTMASK
+* Description : Enables the FAULTMASK priority: Raises the execution priority to -1.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SETFAULTMASK(void)
+{
+ __SETFAULTMASK();
+}
+
+/*******************************************************************************
+* Function Name : NVIC_RESETFAULTMASK
+* Description : Disables the FAULTMASK priority.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_RESETFAULTMASK(void)
+{
+ __RESETFAULTMASK();
+}
+
+/*******************************************************************************
+* Function Name : NVIC_BASEPRICONFIG
+* Description : The execution priority can be changed from 15 (lowest
+ configurable priority) to 1. Writing a zero value will disable
+* the mask of execution priority.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_BASEPRICONFIG(u32 NewPriority)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_BASE_PRI(NewPriority));
+
+ __BASEPRICONFIG(NewPriority << 0x04);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetBASEPRI
+* Description : Returns the BASEPRI mask value.
+* Input : None
+* Output : None
+* Return : BASEPRI register value
+*******************************************************************************/
+u32 NVIC_GetBASEPRI(void)
+{
+ return (__GetBASEPRI());
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetCurrentPendingIRQChannel
+* Description : Returns the current pending IRQ channel identifier.
+* Input : None
+* Output : None
+* Return : Pending IRQ Channel Identifier.
+*******************************************************************************/
+u16 NVIC_GetCurrentPendingIRQChannel(void)
+{
+ return ((u16)((SCB->ICSR & (u32)0x003FF000) >> 0x0C));
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetIRQChannelPendingBitStatus
+* Description : Checks whether the specified IRQ Channel pending bit is set
+* or not.
+* Input : - NVIC_IRQChannel: specifies the interrupt pending bit to check.
+* Output : None
+* Return : The new state of IRQ Channel pending bit(SET or RESET).
+*******************************************************************************/
+ITStatus NVIC_GetIRQChannelPendingBitStatus(u8 NVIC_IRQChannel)
+{
+ ITStatus pendingirqstatus = RESET;
+ u32 tmp = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_IRQChannel));
+
+ tmp = ((u32)0x01 << (NVIC_IRQChannel & (u32)0x1F));
+
+ if (((NVIC->ISPR[(NVIC_IRQChannel >> 0x05)]) & tmp) == tmp)
+ {
+ pendingirqstatus = SET;
+ }
+ else
+ {
+ pendingirqstatus = RESET;
+ }
+ return pendingirqstatus;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SetIRQChannelPendingBit
+* Description : Sets the NVIC’s interrupt pending bit.
+* Input : - NVIC_IRQChannel: specifies the interrupt pending bit to Set.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SetIRQChannelPendingBit(u8 NVIC_IRQChannel)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_IRQChannel));
+
+ *(vu32*) 0xE000EF00 = (u32)NVIC_IRQChannel;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_ClearIRQChannelPendingBit
+* Description : Clears the NVIC’s interrupt pending bit.
+* Input : - NVIC_IRQChannel: specifies the interrupt pending bit to clear.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_ClearIRQChannelPendingBit(u8 NVIC_IRQChannel)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_IRQChannel));
+
+ NVIC->ICPR[(NVIC_IRQChannel >> 0x05)] = (u32)0x01 << (NVIC_IRQChannel & (u32)0x1F);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetCurrentActiveHandler
+* Description : Returns the current active Handler (IRQ Channel and
+* SystemHandler) identifier.
+* Input : None
+* Output : None
+* Return : Active Handler Identifier.
+*******************************************************************************/
+u16 NVIC_GetCurrentActiveHandler(void)
+{
+ return ((u16)(SCB->ICSR & (u32)0x3FF));
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetIRQChannelActiveBitStatus
+* Description : Checks whether the specified IRQ Channel active bit is set
+* or not.
+* Input : - NVIC_IRQChannel: specifies the interrupt active bit to check.
+* Output : None
+* Return : The new state of IRQ Channel active bit(SET or RESET).
+*******************************************************************************/
+ITStatus NVIC_GetIRQChannelActiveBitStatus(u8 NVIC_IRQChannel)
+{
+ ITStatus activeirqstatus = RESET;
+ u32 tmp = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_IRQChannel));
+
+ tmp = ((u32)0x01 << (NVIC_IRQChannel & (u32)0x1F));
+
+ if (((NVIC->IABR[(NVIC_IRQChannel >> 0x05)]) & tmp) == tmp )
+ {
+ activeirqstatus = SET;
+ }
+ else
+ {
+ activeirqstatus = RESET;
+ }
+ return activeirqstatus;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetCPUID
+* Description : Returns the ID number, the version number and the implementation
+* details of the Cortex-M3 core.
+* Input : None
+* Output : None
+* Return : CPU ID.
+*******************************************************************************/
+u32 NVIC_GetCPUID(void)
+{
+ return (SCB->CPUID);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SetVectorTable
+* Description : Sets the vector table location and Offset.
+* Input : - NVIC_VectTab: specifies if the vector table is in RAM or
+* FLASH memory.
+* This parameter can be one of the following values:
+* - NVIC_VectTab_RAM
+* - NVIC_VectTab_FLASH
+* - Offset: Vector Table base offset field.
+* This value must be a multiple of 0x100.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SetVectorTable(u32 NVIC_VectTab, u32 Offset)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_VECTTAB(NVIC_VectTab));
+ assert_param(IS_NVIC_OFFSET(Offset));
+
+ SCB->VTOR = NVIC_VectTab | (Offset & (u32)0x1FFFFF80);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GenerateSystemReset
+* Description : Generates a system reset.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_GenerateSystemReset(void)
+{
+ SCB->AIRCR = AIRCR_VECTKEY_MASK | (u32)0x04;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GenerateCoreReset
+* Description : Generates a Core (Core + NVIC) reset.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_GenerateCoreReset(void)
+{
+ SCB->AIRCR = AIRCR_VECTKEY_MASK | (u32)0x01;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SystemLPConfig
+* Description : Selects the condition for the system to enter low power mode.
+* Input : - LowPowerMode: Specifies the new mode for the system to enter
+* low power mode.
+* This parameter can be one of the following values:
+* - NVIC_LP_SEVONPEND
+* - NVIC_LP_SLEEPDEEP
+* - NVIC_LP_SLEEPONEXIT
+* - NewState: new state of LP condition.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SystemLPConfig(u8 LowPowerMode, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_NVIC_LP(LowPowerMode));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ SCB->SCR |= LowPowerMode;
+ }
+ else
+ {
+ SCB->SCR &= (u32)(~(u32)LowPowerMode);
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SystemHandlerConfig
+* Description : Enables or disables the specified System Handlers.
+* Input : - SystemHandler: specifies the system handler to be enabled
+* or disabled.
+* This parameter can be one of the following values:
+* - SystemHandler_MemoryManage
+* - SystemHandler_BusFault
+* - SystemHandler_UsageFault
+* - NewState: new state of specified System Handlers.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SystemHandlerConfig(u32 SystemHandler, FunctionalState NewState)
+{
+ u32 tmpreg = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_CONFIG_SYSTEM_HANDLER(SystemHandler));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ tmpreg = (u32)0x01 << (SystemHandler & (u32)0x1F);
+
+ if (NewState != DISABLE)
+ {
+ SCB->SHCSR |= tmpreg;
+ }
+ else
+ {
+ SCB->SHCSR &= ~tmpreg;
+ }
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SystemHandlerPriorityConfig
+* Description : Configures the specified System Handlers priority.
+* Input : - SystemHandler: specifies the system handler to be
+* enabled or disabled.
+* This parameter can be one of the following values:
+* - SystemHandler_MemoryManage
+* - SystemHandler_BusFault
+* - SystemHandler_UsageFault
+* - SystemHandler_SVCall
+* - SystemHandler_DebugMonitor
+* - SystemHandler_PSV
+* - SystemHandler_SysTick
+* - SystemHandlerPreemptionPriority: new priority group of the
+* specified system handlers.
+* - SystemHandlerSubPriority: new sub priority of the specified
+* system handlers.
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SystemHandlerPriorityConfig(u32 SystemHandler, u8 SystemHandlerPreemptionPriority,
+ u8 SystemHandlerSubPriority)
+{
+ u32 tmp1 = 0x00, tmp2 = 0xFF, handlermask = 0x00;
+ u32 tmppriority = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_PRIORITY_SYSTEM_HANDLER(SystemHandler));
+ assert_param(IS_NVIC_PREEMPTION_PRIORITY(SystemHandlerPreemptionPriority));
+ assert_param(IS_NVIC_SUB_PRIORITY(SystemHandlerSubPriority));
+
+ tmppriority = (0x700 - (SCB->AIRCR & (u32)0x700))>> 0x08;
+ tmp1 = (0x4 - tmppriority);
+ tmp2 = tmp2 >> tmppriority;
+
+ tmppriority = (u32)SystemHandlerPreemptionPriority << tmp1;
+ tmppriority |= SystemHandlerSubPriority & tmp2;
+
+ tmppriority = tmppriority << 0x04;
+ tmp1 = SystemHandler & (u32)0xC0;
+ tmp1 = tmp1 >> 0x06;
+ tmp2 = (SystemHandler >> 0x08) & (u32)0x03;
+ tmppriority = tmppriority << (tmp2 * 0x08);
+ handlermask = (u32)0xFF << (tmp2 * 0x08);
+
+ SCB->SHPR[tmp1] &= ~handlermask;
+ SCB->SHPR[tmp1] |= tmppriority;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetSystemHandlerPendingBitStatus
+* Description : Checks whether the specified System handlers pending bit is
+* set or not.
+* Input : - SystemHandler: specifies the system handler pending bit to
+* check.
+* This parameter can be one of the following values:
+* - SystemHandler_MemoryManage
+* - SystemHandler_BusFault
+* - SystemHandler_SVCall
+* Output : None
+* Return : The new state of System Handler pending bit(SET or RESET).
+*******************************************************************************/
+ITStatus NVIC_GetSystemHandlerPendingBitStatus(u32 SystemHandler)
+{
+ ITStatus bitstatus = RESET;
+ u32 tmp = 0x00, tmppos = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GET_PENDING_SYSTEM_HANDLER(SystemHandler));
+
+ tmppos = (SystemHandler >> 0x0A);
+ tmppos &= (u32)0x0F;
+
+ tmppos = (u32)0x01 << tmppos;
+
+ tmp = SCB->SHCSR & tmppos;
+
+ if (tmp == tmppos)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_SetSystemHandlerPendingBit
+* Description : Sets System Handler pending bit.
+* Input : - SystemHandler: specifies the system handler pending bit
+* to be set.
+* This parameter can be one of the following values:
+* - SystemHandler_NMI
+* - SystemHandler_PSV
+* - SystemHandler_SysTick
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_SetSystemHandlerPendingBit(u32 SystemHandler)
+{
+ u32 tmp = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_SET_PENDING_SYSTEM_HANDLER(SystemHandler));
+
+ /* Get the System Handler pending bit position */
+ tmp = SystemHandler & (u32)0x1F;
+ /* Set the corresponding System Handler pending bit */
+ SCB->ICSR |= ((u32)0x01 << tmp);
+}
+
+/*******************************************************************************
+* Function Name : NVIC_ClearSystemHandlerPendingBit
+* Description : Clears System Handler pending bit.
+* Input : - SystemHandler: specifies the system handler pending bit to
+* be clear.
+* This parameter can be one of the following values:
+* - SystemHandler_PSV
+* - SystemHandler_SysTick
+* Output : None
+* Return : None
+*******************************************************************************/
+void NVIC_ClearSystemHandlerPendingBit(u32 SystemHandler)
+{
+ u32 tmp = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_CLEAR_SYSTEM_HANDLER(SystemHandler));
+
+ /* Get the System Handler pending bit position */
+ tmp = SystemHandler & (u32)0x1F;
+ /* Clear the corresponding System Handler pending bit */
+ SCB->ICSR |= ((u32)0x01 << (tmp - 0x01));
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetSystemHandlerActiveBitStatus
+* Description : Checks whether the specified System handlers active bit is
+* set or not.
+* Input : - SystemHandler: specifies the system handler active bit to
+* check.
+* This parameter can be one of the following values:
+* - SystemHandler_MemoryManage
+* - SystemHandler_BusFault
+* - SystemHandler_UsageFault
+* - SystemHandler_SVCall
+* - SystemHandler_DebugMonitor
+* - SystemHandler_PSV
+* - SystemHandler_SysTick
+* Output : None
+* Return : The new state of System Handler active bit(SET or RESET).
+*******************************************************************************/
+ITStatus NVIC_GetSystemHandlerActiveBitStatus(u32 SystemHandler)
+{
+ ITStatus bitstatus = RESET;
+
+ u32 tmp = 0x00, tmppos = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_GET_ACTIVE_SYSTEM_HANDLER(SystemHandler));
+
+ tmppos = (SystemHandler >> 0x0E) & (u32)0x0F;
+
+ tmppos = (u32)0x01 << tmppos;
+
+ tmp = SCB->SHCSR & tmppos;
+
+ if (tmp == tmppos)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetFaultHandlerSources
+* Description : Returns the system fault handlers sources.
+* Input : - SystemHandler: specifies the system handler to get its fault
+* sources.
+* This parameter can be one of the following values:
+* - SystemHandler_HardFault
+* - SystemHandler_MemoryManage
+* - SystemHandler_BusFault
+* - SystemHandler_UsageFault
+* - SystemHandler_DebugMonitor
+* Output : None
+* Return : Source of the fault handler.
+*******************************************************************************/
+u32 NVIC_GetFaultHandlerSources(u32 SystemHandler)
+{
+ u32 faultsources = 0x00;
+ u32 tmpreg = 0x00, tmppos = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_FAULT_SOURCE_SYSTEM_HANDLER(SystemHandler));
+
+ tmpreg = (SystemHandler >> 0x12) & (u32)0x03;
+ tmppos = (SystemHandler >> 0x14) & (u32)0x03;
+
+ if (tmpreg == 0x00)
+ {
+ faultsources = SCB->HFSR;
+ }
+ else if (tmpreg == 0x01)
+ {
+ faultsources = SCB->CFSR >> (tmppos * 0x08);
+ if (tmppos != 0x02)
+ {
+ faultsources &= (u32)0x0F;
+ }
+ else
+ {
+ faultsources &= (u32)0xFF;
+ }
+ }
+ else
+ {
+ faultsources = SCB->DFSR;
+ }
+ return faultsources;
+}
+
+/*******************************************************************************
+* Function Name : NVIC_GetFaultAddress
+* Description : Returns the address of the location that generated a fault
+* handler.
+* Input : - SystemHandler: specifies the system handler to get its
+* fault address.
+* This parameter can be one of the following values:
+* - SystemHandler_MemoryManage
+* - SystemHandler_BusFault
+* Output : None
+* Return : Fault address.
+*******************************************************************************/
+u32 NVIC_GetFaultAddress(u32 SystemHandler)
+{
+ u32 faultaddress = 0x00;
+ u32 tmp = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_FAULT_ADDRESS_SYSTEM_HANDLER(SystemHandler));
+
+ tmp = (SystemHandler >> 0x16) & (u32)0x01;
+
+ if (tmp == 0x00)
+ {
+ faultaddress = SCB->MMFAR;
+ }
+ else
+ {
+ faultaddress = SCB->BFAR;
+ }
+ return faultaddress;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_nvic.lst b/src/stm32lib/src/stm32f10x_nvic.lst new file mode 100644 index 0000000..4eeda03 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_nvic.lst @@ -0,0 +1,1980 @@ + 1 .syntax unified + 2 .cpu cortex-m3 + 3 .fpu softvfp + 4 .eabi_attribute 20, 1 + 5 .eabi_attribute 21, 1 + 6 .eabi_attribute 23, 3 + 7 .eabi_attribute 24, 1 + 8 .eabi_attribute 25, 1 + 9 .eabi_attribute 26, 1 + 10 .eabi_attribute 30, 4 + 11 .eabi_attribute 18, 4 + 12 .thumb + 13 .file "stm32f10x_nvic.c" + 21 .Ltext0: + 22 .align 2 + 23 .global NVIC_DeInit + 24 .thumb + 25 .thumb_func + 27 NVIC_DeInit: + 28 .LFB23: + 29 .file 1 "stm32lib/src/stm32f10x_nvic.c" + 1:stm32lib/src/stm32f10x_nvic.c **** /******************** (C) COPYRIGHT 2008 STMicroelectronics ******************** + 2:stm32lib/src/stm32f10x_nvic.c **** * File Name : stm32f10x_nvic.c + 3:stm32lib/src/stm32f10x_nvic.c **** * Author : MCD Application Team + 4:stm32lib/src/stm32f10x_nvic.c **** * Version : V2.0.2 + 5:stm32lib/src/stm32f10x_nvic.c **** * Date : 07/11/2008 + 6:stm32lib/src/stm32f10x_nvic.c **** * Description : This file provides all the NVIC firmware functions. + 7:stm32lib/src/stm32f10x_nvic.c **** ******************************************************************************** + 8:stm32lib/src/stm32f10x_nvic.c **** * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + 9:stm32lib/src/stm32f10x_nvic.c **** * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. + 10:stm32lib/src/stm32f10x_nvic.c **** * AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, + 11:stm32lib/src/stm32f10x_nvic.c **** * INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE + 12:stm32lib/src/stm32f10x_nvic.c **** * CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING + 13:stm32lib/src/stm32f10x_nvic.c **** * INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + 14:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 15:stm32lib/src/stm32f10x_nvic.c **** + 16:stm32lib/src/stm32f10x_nvic.c **** /* Includes ------------------------------------------------------------------*/ + 17:stm32lib/src/stm32f10x_nvic.c **** #include "stm32f10x_nvic.h" + 18:stm32lib/src/stm32f10x_nvic.c **** + 19:stm32lib/src/stm32f10x_nvic.c **** /* Private typedef -----------------------------------------------------------*/ + 20:stm32lib/src/stm32f10x_nvic.c **** /* Private define ------------------------------------------------------------*/ + 21:stm32lib/src/stm32f10x_nvic.c **** #define AIRCR_VECTKEY_MASK ((u32)0x05FA0000) + 22:stm32lib/src/stm32f10x_nvic.c **** + 23:stm32lib/src/stm32f10x_nvic.c **** /* Private macro -------------------------------------------------------------*/ + 24:stm32lib/src/stm32f10x_nvic.c **** /* Private variables ---------------------------------------------------------*/ + 25:stm32lib/src/stm32f10x_nvic.c **** /* Private function prototypes -----------------------------------------------*/ + 26:stm32lib/src/stm32f10x_nvic.c **** /* Private functions ---------------------------------------------------------*/ + 27:stm32lib/src/stm32f10x_nvic.c **** + 28:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 29:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_DeInit + 30:stm32lib/src/stm32f10x_nvic.c **** * Description : Deinitializes the NVIC peripheral registers to their default + 31:stm32lib/src/stm32f10x_nvic.c **** * reset values. + 32:stm32lib/src/stm32f10x_nvic.c **** * Input : None + 33:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 34:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 35:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 36:stm32lib/src/stm32f10x_nvic.c **** void NVIC_DeInit(void) + 37:stm32lib/src/stm32f10x_nvic.c **** { + 30 .loc 1 37 0 + 31 @ args = 0, pretend = 0, frame = 0 + 32 @ frame_needed = 0, uses_anonymous_args = 0 + 33 @ link register save eliminated. + 38:stm32lib/src/stm32f10x_nvic.c **** u32 index = 0; + 39:stm32lib/src/stm32f10x_nvic.c **** + 40:stm32lib/src/stm32f10x_nvic.c **** NVIC->ICER[0] = 0xFFFFFFFF; + 34 .loc 1 40 0 + 35 0000 0B4B ldr r3, .L4 + 36 0002 4FF0FF31 mov r1, #-1 + 41:stm32lib/src/stm32f10x_nvic.c **** NVIC->ICER[1] = 0x0FFFFFFF; + 37 .loc 1 41 0 + 38 0006 6FF07042 mvn r2, #-268435456 + 39 .loc 1 40 0 + 40 000a C3F88010 str r1, [r3, #128] + 42:stm32lib/src/stm32f10x_nvic.c **** NVIC->ICPR[0] = 0xFFFFFFFF; + 43:stm32lib/src/stm32f10x_nvic.c **** NVIC->ICPR[1] = 0x0FFFFFFF; + 41 .loc 1 43 0 + 42 000e 0020 movs r0, #0 + 43 .LVL0: + 44 .loc 1 41 0 + 45 0010 C3F88420 str r2, [r3, #132] + 46 .loc 1 42 0 + 47 0014 C3F88011 str r1, [r3, #384] + 48 .loc 1 43 0 + 49 0018 C3F88421 str r2, [r3, #388] + 50 .L2: + 44:stm32lib/src/stm32f10x_nvic.c **** + 45:stm32lib/src/stm32f10x_nvic.c **** for(index = 0; index < 0x0F; index++) + 46:stm32lib/src/stm32f10x_nvic.c **** { + 47:stm32lib/src/stm32f10x_nvic.c **** NVIC->IPR[index] = 0x00000000; + 51 .loc 1 47 0 + 52 001c 00F1C001 add r1, r0, #192 + 53 0020 034B ldr r3, .L4 + 54 .loc 1 45 0 + 55 0022 0130 adds r0, r0, #1 + 56 .loc 1 47 0 + 57 0024 0022 movs r2, #0 + 58 .loc 1 45 0 + 59 0026 0F28 cmp r0, #15 + 60 .loc 1 47 0 + 61 0028 43F82120 str r2, [r3, r1, lsl #2] + 62 .loc 1 45 0 + 63 002c F6D1 bne .L2 + 48:stm32lib/src/stm32f10x_nvic.c **** } + 49:stm32lib/src/stm32f10x_nvic.c **** } + 64 .loc 1 49 0 + 65 002e 7047 bx lr + 66 .L5: + 67 .align 2 + 68 .L4: + 69 0030 00E100E0 .word -536813312 + 70 .LFE23: + 72 .align 2 + 73 .global NVIC_SCBDeInit + 74 .thumb + 75 .thumb_func + 77 NVIC_SCBDeInit: + 78 .LFB24: + 50:stm32lib/src/stm32f10x_nvic.c **** + 51:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 52:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_SCBDeInit + 53:stm32lib/src/stm32f10x_nvic.c **** * Description : Deinitializes the SCB peripheral registers to their default + 54:stm32lib/src/stm32f10x_nvic.c **** * reset values. + 55:stm32lib/src/stm32f10x_nvic.c **** * Input : None + 56:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 57:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 58:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 59:stm32lib/src/stm32f10x_nvic.c **** void NVIC_SCBDeInit(void) + 60:stm32lib/src/stm32f10x_nvic.c **** { + 79 .loc 1 60 0 + 80 @ args = 0, pretend = 0, frame = 0 + 81 @ frame_needed = 0, uses_anonymous_args = 0 + 82 @ link register save eliminated. + 61:stm32lib/src/stm32f10x_nvic.c **** u32 index = 0x00; + 62:stm32lib/src/stm32f10x_nvic.c **** + 63:stm32lib/src/stm32f10x_nvic.c **** SCB->ICSR = 0x0A000000; + 83 .loc 1 63 0 + 84 0034 094A ldr r2, .L8 + 85 0036 4FF02063 mov r3, #167772160 + 64:stm32lib/src/stm32f10x_nvic.c **** SCB->VTOR = 0x00000000; + 65:stm32lib/src/stm32f10x_nvic.c **** SCB->AIRCR = AIRCR_VECTKEY_MASK; + 86 .loc 1 65 0 + 87 003a 0949 ldr r1, .L8+4 + 88 .loc 1 63 0 + 89 003c 5360 str r3, [r2, #4] + 90 .loc 1 64 0 + 91 003e 03F17643 add r3, r3, #-167772160 + 92 0042 9360 str r3, [r2, #8] + 93 .loc 1 65 0 + 94 0044 D160 str r1, [r2, #12] + 66:stm32lib/src/stm32f10x_nvic.c **** SCB->SCR = 0x00000000; + 95 .loc 1 66 0 + 96 0046 1361 str r3, [r2, #16] + 67:stm32lib/src/stm32f10x_nvic.c **** SCB->CCR = 0x00000000; + 97 .loc 1 67 0 + 98 0048 5361 str r3, [r2, #20] + 68:stm32lib/src/stm32f10x_nvic.c **** for(index = 0; index < 0x03; index++) + 69:stm32lib/src/stm32f10x_nvic.c **** { + 70:stm32lib/src/stm32f10x_nvic.c **** SCB->SHPR[index] = 0; + 99 .loc 1 70 0 + 100 004a 9361 str r3, [r2, #24] + 101 004c D361 str r3, [r2, #28] + 102 004e 1362 str r3, [r2, #32] + 71:stm32lib/src/stm32f10x_nvic.c **** } + 72:stm32lib/src/stm32f10x_nvic.c **** SCB->SHCSR = 0x00000000; + 103 .loc 1 72 0 + 104 0050 5362 str r3, [r2, #36] + 73:stm32lib/src/stm32f10x_nvic.c **** SCB->CFSR = 0xFFFFFFFF; + 105 .loc 1 73 0 + 106 0052 013B subs r3, r3, #1 + 107 0054 9362 str r3, [r2, #40] + 74:stm32lib/src/stm32f10x_nvic.c **** SCB->HFSR = 0xFFFFFFFF; + 108 .loc 1 74 0 + 109 0056 D362 str r3, [r2, #44] + 75:stm32lib/src/stm32f10x_nvic.c **** SCB->DFSR = 0xFFFFFFFF; + 110 .loc 1 75 0 + 111 0058 1363 str r3, [r2, #48] + 76:stm32lib/src/stm32f10x_nvic.c **** } + 112 .loc 1 76 0 + 113 005a 7047 bx lr + 114 .L9: + 115 .align 2 + 116 .L8: + 117 005c 00ED00E0 .word -536810240 + 118 0060 0000FA05 .word 100270080 + 119 .LFE24: + 121 .align 2 + 122 .global NVIC_PriorityGroupConfig + 123 .thumb + 124 .thumb_func + 126 NVIC_PriorityGroupConfig: + 127 .LFB25: + 77:stm32lib/src/stm32f10x_nvic.c **** + 78:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 79:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_PriorityGroupConfig + 80:stm32lib/src/stm32f10x_nvic.c **** * Description : Configures the priority grouping: pre-emption priority + 81:stm32lib/src/stm32f10x_nvic.c **** * and subpriority. + 82:stm32lib/src/stm32f10x_nvic.c **** * Input : - NVIC_PriorityGroup: specifies the priority grouping bits + 83:stm32lib/src/stm32f10x_nvic.c **** * length. This parameter can be one of the following values: + 84:stm32lib/src/stm32f10x_nvic.c **** * - NVIC_PriorityGroup_0: 0 bits for pre-emption priority + 85:stm32lib/src/stm32f10x_nvic.c **** * 4 bits for subpriority + 86:stm32lib/src/stm32f10x_nvic.c **** * - NVIC_PriorityGroup_1: 1 bits for pre-emption priority + 87:stm32lib/src/stm32f10x_nvic.c **** * 3 bits for subpriority + 88:stm32lib/src/stm32f10x_nvic.c **** * - NVIC_PriorityGroup_2: 2 bits for pre-emption priority + 89:stm32lib/src/stm32f10x_nvic.c **** * 2 bits for subpriority + 90:stm32lib/src/stm32f10x_nvic.c **** * - NVIC_PriorityGroup_3: 3 bits for pre-emption priority + 91:stm32lib/src/stm32f10x_nvic.c **** * 1 bits for subpriority + 92:stm32lib/src/stm32f10x_nvic.c **** * - NVIC_PriorityGroup_4: 4 bits for pre-emption priority + 93:stm32lib/src/stm32f10x_nvic.c **** * 0 bits for subpriority + 94:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 95:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 96:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 97:stm32lib/src/stm32f10x_nvic.c **** void NVIC_PriorityGroupConfig(u32 NVIC_PriorityGroup) + 98:stm32lib/src/stm32f10x_nvic.c **** { + 128 .loc 1 98 0 + 129 @ args = 0, pretend = 0, frame = 0 + 130 @ frame_needed = 0, uses_anonymous_args = 0 + 131 @ link register save eliminated. + 132 .LVL1: + 99:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 100:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_NVIC_PRIORITY_GROUP(NVIC_PriorityGroup)); + 101:stm32lib/src/stm32f10x_nvic.c **** + 102:stm32lib/src/stm32f10x_nvic.c **** /* Set the PRIGROUP[10:8] bits according to NVIC_PriorityGroup value */ + 103:stm32lib/src/stm32f10x_nvic.c **** SCB->AIRCR = AIRCR_VECTKEY_MASK | NVIC_PriorityGroup; + 133 .loc 1 103 0 + 134 0064 40F0BE60 orr r0, r0, #99614720 + 135 .LVL2: + 136 0068 024B ldr r3, .L12 + 137 006a 40F42020 orr r0, r0, #655360 + 138 006e D860 str r0, [r3, #12] + 104:stm32lib/src/stm32f10x_nvic.c **** } + 139 .loc 1 104 0 + 140 0070 7047 bx lr + 141 .L13: + 142 0072 00BF .align 2 + 143 .L12: + 144 0074 00ED00E0 .word -536810240 + 145 .LFE25: + 147 .align 2 + 148 .global NVIC_Init + 149 .thumb + 150 .thumb_func + 152 NVIC_Init: + 153 .LFB26: + 105:stm32lib/src/stm32f10x_nvic.c **** + 106:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 107:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_Init + 108:stm32lib/src/stm32f10x_nvic.c **** * Description : Initializes the NVIC peripheral according to the specified + 109:stm32lib/src/stm32f10x_nvic.c **** * parameters in the NVIC_InitStruct. + 110:stm32lib/src/stm32f10x_nvic.c **** * Input : - NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure + 111:stm32lib/src/stm32f10x_nvic.c **** * that contains the configuration information for the + 112:stm32lib/src/stm32f10x_nvic.c **** * specified NVIC peripheral. + 113:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 114:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 115:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 116:stm32lib/src/stm32f10x_nvic.c **** void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct) + 117:stm32lib/src/stm32f10x_nvic.c **** { + 154 .loc 1 117 0 + 155 @ args = 0, pretend = 0, frame = 0 + 156 @ frame_needed = 0, uses_anonymous_args = 0 + 157 .LVL3: + 158 0078 30B5 push {r4, r5, lr} + 159 .LCFI0: + 118:stm32lib/src/stm32f10x_nvic.c **** u32 tmppriority = 0x00, tmpreg = 0x00, tmpmask = 0x00; + 119:stm32lib/src/stm32f10x_nvic.c **** u32 tmppre = 0, tmpsub = 0x0F; + 120:stm32lib/src/stm32f10x_nvic.c **** + 121:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 122:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_FUNCTIONAL_STATE(NVIC_InitStruct->NVIC_IRQChannelCmd)); + 123:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_InitStruct->NVIC_IRQChannel)); + 124:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_NVIC_PREEMPTION_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority)); + 125:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_NVIC_SUB_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelSubPriority)); + 126:stm32lib/src/stm32f10x_nvic.c **** + 127:stm32lib/src/stm32f10x_nvic.c **** if (NVIC_InitStruct->NVIC_IRQChannelCmd != DISABLE) + 160 .loc 1 127 0 + 161 007a C378 ldrb r3, [r0, #3] @ zero_extendqisi2 + 162 007c 90F800C0 ldrb ip, [r0, #0] @ zero_extendqisi2 + 163 0080 4BB3 cbz r3, .L15 + 128:stm32lib/src/stm32f10x_nvic.c **** { + 129:stm32lib/src/stm32f10x_nvic.c **** /* Compute the Corresponding IRQ Priority --------------------------------*/ + 130:stm32lib/src/stm32f10x_nvic.c **** tmppriority = (0x700 - (SCB->AIRCR & (u32)0x700))>> 0x08; + 164 .loc 1 130 0 + 165 0082 1A4B ldr r3, .L18 + 131:stm32lib/src/stm32f10x_nvic.c **** tmppre = (0x4 - tmppriority); + 132:stm32lib/src/stm32f10x_nvic.c **** tmpsub = tmpsub >> tmppriority; + 133:stm32lib/src/stm32f10x_nvic.c **** + 134:stm32lib/src/stm32f10x_nvic.c **** tmppriority = (u32)NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority << tmppre; + 166 .loc 1 134 0 + 167 0084 4178 ldrb r1, [r0, #1] @ zero_extendqisi2 + 168 .loc 1 130 0 + 169 0086 DA68 ldr r2, [r3, #12] + 135:stm32lib/src/stm32f10x_nvic.c **** tmppriority |= NVIC_InitStruct->NVIC_IRQChannelSubPriority & tmpsub; + 136:stm32lib/src/stm32f10x_nvic.c **** + 137:stm32lib/src/stm32f10x_nvic.c **** tmppriority = tmppriority << 0x04; + 138:stm32lib/src/stm32f10x_nvic.c **** tmppriority = ((u32)tmppriority) << ((NVIC_InitStruct->NVIC_IRQChannel & (u8)0x03) * 0x08); + 139:stm32lib/src/stm32f10x_nvic.c **** + 140:stm32lib/src/stm32f10x_nvic.c **** tmpreg = NVIC->IPR[(NVIC_InitStruct->NVIC_IRQChannel >> 0x02)]; + 170 .loc 1 140 0 + 171 0088 194D ldr r5, .L18+4 + 172 .loc 1 130 0 + 173 008a D243 mvns r2, r2 + 174 008c C2F30222 ubfx r2, r2, #8, #3 + 175 .LVL4: + 176 .loc 1 134 0 + 177 0090 C2F10403 rsb r3, r2, #4 + 178 0094 9940 lsls r1, r1, r3 + 179 .LVL5: + 180 .loc 1 135 0 + 181 0096 0F23 movs r3, #15 + 182 0098 D340 lsrs r3, r3, r2 + 183 009a 8278 ldrb r2, [r0, #2] @ zero_extendqisi2 + 184 .loc 1 138 0 + 185 009c 0CF00300 and r0, ip, #3 + 186 .LVL6: + 187 .loc 1 135 0 + 188 00a0 1340 ands r3, r3, r2 + 189 00a2 0B43 orrs r3, r3, r1 + 190 .LVL7: + 191 .loc 1 138 0 + 192 00a4 C000 lsls r0, r0, #3 + 193 .loc 1 137 0 + 194 00a6 1B01 lsls r3, r3, #4 + 195 .LVL8: + 141:stm32lib/src/stm32f10x_nvic.c **** tmpmask = (u32)0xFF << ((NVIC_InitStruct->NVIC_IRQChannel & (u8)0x03) * 0x08); + 196 .loc 1 141 0 + 197 00a8 FF22 movs r2, #255 + 198 00aa 8240 lsls r2, r2, r0 + 199 .LVL9: + 200 .loc 1 138 0 + 201 00ac 8340 lsls r3, r3, r0 + 202 .LVL10: + 203 .loc 1 140 0 + 204 00ae 4FEA9C04 lsr r4, ip, #2 + 205 00b2 C034 adds r4, r4, #192 + 206 00b4 55F82410 ldr r1, [r5, r4, lsl #2] + 207 .LVL11: + 142:stm32lib/src/stm32f10x_nvic.c **** tmpreg &= ~tmpmask; + 143:stm32lib/src/stm32f10x_nvic.c **** tmppriority &= tmpmask; + 144:stm32lib/src/stm32f10x_nvic.c **** tmpreg |= tmppriority; + 208 .loc 1 144 0 + 209 00b8 1340 ands r3, r3, r2 + 210 .LVL12: + 211 .loc 1 142 0 + 212 00ba 21EA0201 bic r1, r1, r2 + 213 .LVL13: + 214 .loc 1 144 0 + 215 00be 0B43 orrs r3, r3, r1 + 216 .LVL14: + 145:stm32lib/src/stm32f10x_nvic.c **** + 146:stm32lib/src/stm32f10x_nvic.c **** NVIC->IPR[(NVIC_InitStruct->NVIC_IRQChannel >> 0x02)] = tmpreg; + 217 .loc 1 146 0 + 218 00c0 45F82430 str r3, [r5, r4, lsl #2] + 147:stm32lib/src/stm32f10x_nvic.c **** + 148:stm32lib/src/stm32f10x_nvic.c **** /* Enable the Selected IRQ Channels --------------------------------------*/ + 149:stm32lib/src/stm32f10x_nvic.c **** NVIC->ISER[(NVIC_InitStruct->NVIC_IRQChannel >> 0x05)] = + 219 .loc 1 149 0 + 220 00c4 0CF01F02 and r2, ip, #31 + 221 .LVL15: + 222 00c8 0123 movs r3, #1 + 223 .LVL16: + 224 00ca 9340 lsls r3, r3, r2 + 225 00cc 4FEA5C11 lsr r1, ip, #5 + 226 00d0 45F82130 str r3, [r5, r1, lsl #2] + 227 00d4 09E0 b .L17 + 228 .LVL17: + 229 .L15: + 150:stm32lib/src/stm32f10x_nvic.c **** (u32)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (u8)0x1F); + 151:stm32lib/src/stm32f10x_nvic.c **** } + 152:stm32lib/src/stm32f10x_nvic.c **** else + 153:stm32lib/src/stm32f10x_nvic.c **** { + 154:stm32lib/src/stm32f10x_nvic.c **** /* Disable the Selected IRQ Channels -------------------------------------*/ + 155:stm32lib/src/stm32f10x_nvic.c **** NVIC->ICER[(NVIC_InitStruct->NVIC_IRQChannel >> 0x05)] = + 230 .loc 1 155 0 + 231 00d6 0CF01F02 and r2, ip, #31 + 232 00da 0123 movs r3, #1 + 233 00dc 9340 lsls r3, r3, r2 + 234 00de 4FEA5C11 lsr r1, ip, #5 + 235 00e2 034A ldr r2, .L18+4 + 236 00e4 2031 adds r1, r1, #32 + 237 00e6 42F82130 str r3, [r2, r1, lsl #2] + 238 .L17: + 156:stm32lib/src/stm32f10x_nvic.c **** (u32)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (u8)0x1F); + 157:stm32lib/src/stm32f10x_nvic.c **** } + 158:stm32lib/src/stm32f10x_nvic.c **** } + 239 .loc 1 158 0 + 240 00ea 30BD pop {r4, r5, pc} + 241 .L19: + 242 .align 2 + 243 .L18: + 244 00ec 00ED00E0 .word -536810240 + 245 00f0 00E100E0 .word -536813312 + 246 .LFE26: + 248 .align 2 + 249 .global NVIC_StructInit + 250 .thumb + 251 .thumb_func + 253 NVIC_StructInit: + 254 .LFB27: + 159:stm32lib/src/stm32f10x_nvic.c **** + 160:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 161:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_StructInit + 162:stm32lib/src/stm32f10x_nvic.c **** * Description : Fills each NVIC_InitStruct member with its default value. + 163:stm32lib/src/stm32f10x_nvic.c **** * Input : - NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure which + 164:stm32lib/src/stm32f10x_nvic.c **** * will be initialized. + 165:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 166:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 167:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 168:stm32lib/src/stm32f10x_nvic.c **** void NVIC_StructInit(NVIC_InitTypeDef* NVIC_InitStruct) + 169:stm32lib/src/stm32f10x_nvic.c **** { + 255 .loc 1 169 0 + 256 @ args = 0, pretend = 0, frame = 0 + 257 @ frame_needed = 0, uses_anonymous_args = 0 + 258 @ link register save eliminated. + 259 .LVL18: + 170:stm32lib/src/stm32f10x_nvic.c **** /* NVIC_InitStruct members default value */ + 171:stm32lib/src/stm32f10x_nvic.c **** NVIC_InitStruct->NVIC_IRQChannel = 0x00; + 260 .loc 1 171 0 + 261 00f4 0023 movs r3, #0 + 262 00f6 0370 strb r3, [r0, #0] + 172:stm32lib/src/stm32f10x_nvic.c **** NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority = 0x00; + 263 .loc 1 172 0 + 264 00f8 4370 strb r3, [r0, #1] + 173:stm32lib/src/stm32f10x_nvic.c **** NVIC_InitStruct->NVIC_IRQChannelSubPriority = 0x00; + 265 .loc 1 173 0 + 266 00fa 8370 strb r3, [r0, #2] + 174:stm32lib/src/stm32f10x_nvic.c **** NVIC_InitStruct->NVIC_IRQChannelCmd = DISABLE; + 267 .loc 1 174 0 + 268 00fc C370 strb r3, [r0, #3] + 175:stm32lib/src/stm32f10x_nvic.c **** } + 269 .loc 1 175 0 + 270 00fe 7047 bx lr + 271 .LFE27: + 273 .align 2 + 274 .global NVIC_SETPRIMASK + 275 .thumb + 276 .thumb_func + 278 NVIC_SETPRIMASK: + 279 .LFB28: + 176:stm32lib/src/stm32f10x_nvic.c **** + 177:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 178:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_SETPRIMASK + 179:stm32lib/src/stm32f10x_nvic.c **** * Description : Enables the PRIMASK priority: Raises the execution priority to 0. + 180:stm32lib/src/stm32f10x_nvic.c **** * Input : None + 181:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 182:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 183:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 184:stm32lib/src/stm32f10x_nvic.c **** void NVIC_SETPRIMASK(void) + 185:stm32lib/src/stm32f10x_nvic.c **** { + 280 .loc 1 185 0 + 281 @ args = 0, pretend = 0, frame = 0 + 282 @ frame_needed = 0, uses_anonymous_args = 0 + 283 @ link register save eliminated. + 284 .LBB4: + 285 .LBB5: + 286 .file 2 "stm32lib/inc/cortexm3_macro.h" + 1:stm32lib/inc/cortexm3_macro.h **** #if 0 + 2:stm32lib/inc/cortexm3_macro.h **** /******************** (C) COPYRIGHT 2008 STMicroelectronics ******************** + 3:stm32lib/inc/cortexm3_macro.h **** * File Name : cortexm3_macro.h + 4:stm32lib/inc/cortexm3_macro.h **** * Author : MCD Application Team + 5:stm32lib/inc/cortexm3_macro.h **** * Version : V2.0.2 + 6:stm32lib/inc/cortexm3_macro.h **** * Date : 07/11/2008 + 7:stm32lib/inc/cortexm3_macro.h **** * Description : Header file for cortexm3_macro.s. + 8:stm32lib/inc/cortexm3_macro.h **** ******************************************************************************** + 9:stm32lib/inc/cortexm3_macro.h **** * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + 10:stm32lib/inc/cortexm3_macro.h **** * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. + 11:stm32lib/inc/cortexm3_macro.h **** * AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, + 12:stm32lib/inc/cortexm3_macro.h **** * INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE + 13:stm32lib/inc/cortexm3_macro.h **** * CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING + 14:stm32lib/inc/cortexm3_macro.h **** * INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + 15:stm32lib/inc/cortexm3_macro.h **** *******************************************************************************/ + 16:stm32lib/inc/cortexm3_macro.h **** + 17:stm32lib/inc/cortexm3_macro.h **** /* Define to prevent recursive inclusion -------------------------------------*/ + 18:stm32lib/inc/cortexm3_macro.h **** #ifndef __CORTEXM3_MACRO_H + 19:stm32lib/inc/cortexm3_macro.h **** #define __CORTEXM3_MACRO_H + 20:stm32lib/inc/cortexm3_macro.h **** + 21:stm32lib/inc/cortexm3_macro.h **** /* Includes ------------------------------------------------------------------*/ + 22:stm32lib/inc/cortexm3_macro.h **** #include "stm32f10x_type.h" + 23:stm32lib/inc/cortexm3_macro.h **** + 24:stm32lib/inc/cortexm3_macro.h **** /* Exported types ------------------------------------------------------------*/ + 25:stm32lib/inc/cortexm3_macro.h **** /* Exported constants --------------------------------------------------------*/ + 26:stm32lib/inc/cortexm3_macro.h **** /* Exported macro ------------------------------------------------------------*/ + 27:stm32lib/inc/cortexm3_macro.h **** /* Exported functions ------------------------------------------------------- */ + 28:stm32lib/inc/cortexm3_macro.h **** void __WFI(void); + 29:stm32lib/inc/cortexm3_macro.h **** void __WFE(void); + 30:stm32lib/inc/cortexm3_macro.h **** void __SEV(void); + 31:stm32lib/inc/cortexm3_macro.h **** void __ISB(void); + 32:stm32lib/inc/cortexm3_macro.h **** void __DSB(void); + 33:stm32lib/inc/cortexm3_macro.h **** void __DMB(void); + 34:stm32lib/inc/cortexm3_macro.h **** void __SVC(void); + 35:stm32lib/inc/cortexm3_macro.h **** u32 __MRS_CONTROL(void); + 36:stm32lib/inc/cortexm3_macro.h **** void __MSR_CONTROL(u32 Control); + 37:stm32lib/inc/cortexm3_macro.h **** u32 __MRS_PSP(void); + 38:stm32lib/inc/cortexm3_macro.h **** void __MSR_PSP(u32 TopOfProcessStack); + 39:stm32lib/inc/cortexm3_macro.h **** u32 __MRS_MSP(void); + 40:stm32lib/inc/cortexm3_macro.h **** void __MSR_MSP(u32 TopOfMainStack); + 41:stm32lib/inc/cortexm3_macro.h **** void __RESETPRIMASK(void); + 42:stm32lib/inc/cortexm3_macro.h **** void __SETPRIMASK(void); + 43:stm32lib/inc/cortexm3_macro.h **** u32 __READ_PRIMASK(void); + 44:stm32lib/inc/cortexm3_macro.h **** void __RESETFAULTMASK(void); + 45:stm32lib/inc/cortexm3_macro.h **** void __SETFAULTMASK(void); + 46:stm32lib/inc/cortexm3_macro.h **** u32 __READ_FAULTMASK(void); + 47:stm32lib/inc/cortexm3_macro.h **** void __BASEPRICONFIG(u32 NewPriority); + 48:stm32lib/inc/cortexm3_macro.h **** u32 __GetBASEPRI(void); + 49:stm32lib/inc/cortexm3_macro.h **** u16 __REV_HalfWord(u16 Data); + 50:stm32lib/inc/cortexm3_macro.h **** u32 __REV_Word(u32 Data); + 51:stm32lib/inc/cortexm3_macro.h **** + 52:stm32lib/inc/cortexm3_macro.h **** #endif /* __CORTEXM3_MACRO_H */ + 53:stm32lib/inc/cortexm3_macro.h **** #endif + 54:stm32lib/inc/cortexm3_macro.h **** + 55:stm32lib/inc/cortexm3_macro.h **** /******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/ + 56:stm32lib/inc/cortexm3_macro.h **** + 57:stm32lib/inc/cortexm3_macro.h **** /******************** (C) COPYRIGHT 2008 Andreas Fritiofson ******************** + 58:stm32lib/inc/cortexm3_macro.h **** * File Name : cortexm3_macro.h + 59:stm32lib/inc/cortexm3_macro.h **** * Author : Andreas Fritiofson + 60:stm32lib/inc/cortexm3_macro.h **** * Version : V1.0 + 61:stm32lib/inc/cortexm3_macro.h **** * Date : 30/04/2008 + 62:stm32lib/inc/cortexm3_macro.h **** * Description : Instruction wrappers for special Cortex-M3 instructions. + 63:stm32lib/inc/cortexm3_macro.h **** ******************************************************************************** + 64:stm32lib/inc/cortexm3_macro.h **** Permission is hereby granted, free of charge, to any person obtaining a copy + 65:stm32lib/inc/cortexm3_macro.h **** of this software and associated documentation files (the "Software"), to deal + 66:stm32lib/inc/cortexm3_macro.h **** in the Software without restriction, including without limitation the rights + 67:stm32lib/inc/cortexm3_macro.h **** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + 68:stm32lib/inc/cortexm3_macro.h **** copies of the Software, and to permit persons to whom the Software is + 69:stm32lib/inc/cortexm3_macro.h **** furnished to do so, subject to the following conditions: + 70:stm32lib/inc/cortexm3_macro.h **** + 71:stm32lib/inc/cortexm3_macro.h **** The above copyright notice and this permission notice shall be included in + 72:stm32lib/inc/cortexm3_macro.h **** all copies or substantial portions of the Software. + 73:stm32lib/inc/cortexm3_macro.h **** + 74:stm32lib/inc/cortexm3_macro.h **** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + 75:stm32lib/inc/cortexm3_macro.h **** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + 76:stm32lib/inc/cortexm3_macro.h **** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + 77:stm32lib/inc/cortexm3_macro.h **** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + 78:stm32lib/inc/cortexm3_macro.h **** LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + 79:stm32lib/inc/cortexm3_macro.h **** OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + 80:stm32lib/inc/cortexm3_macro.h **** THE SOFTWARE. + 81:stm32lib/inc/cortexm3_macro.h **** *******************************************************************************/ + 82:stm32lib/inc/cortexm3_macro.h **** + 83:stm32lib/inc/cortexm3_macro.h **** /* Define to prevent recursive inclusion -------------------------------------*/ + 84:stm32lib/inc/cortexm3_macro.h **** #ifndef __CORTEXM3_MACRO_H + 85:stm32lib/inc/cortexm3_macro.h **** #define __CORTEXM3_MACRO_H + 86:stm32lib/inc/cortexm3_macro.h **** + 87:stm32lib/inc/cortexm3_macro.h **** /* Includes ------------------------------------------------------------------*/ + 88:stm32lib/inc/cortexm3_macro.h **** #include "stm32f10x_type.h" + 89:stm32lib/inc/cortexm3_macro.h **** + 90:stm32lib/inc/cortexm3_macro.h **** /* Exported types ------------------------------------------------------------*/ + 91:stm32lib/inc/cortexm3_macro.h **** /* Exported constants --------------------------------------------------------*/ + 92:stm32lib/inc/cortexm3_macro.h **** /* Exported macro ------------------------------------------------------------*/ + 93:stm32lib/inc/cortexm3_macro.h **** /* Exported functions ------------------------------------------------------- */ + 94:stm32lib/inc/cortexm3_macro.h **** static inline void __WFI(void) { + 95:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "WFI \n" ); + 96:stm32lib/inc/cortexm3_macro.h **** } + 97:stm32lib/inc/cortexm3_macro.h **** static inline void __WFE(void) { + 98:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "WFE \n" ); + 99:stm32lib/inc/cortexm3_macro.h **** } + 100:stm32lib/inc/cortexm3_macro.h **** static inline void __SEV(void) { + 101:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "SEV \n" ); + 102:stm32lib/inc/cortexm3_macro.h **** } + 103:stm32lib/inc/cortexm3_macro.h **** static inline void __ISB(void) { + 104:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "ISB \n" ); + 105:stm32lib/inc/cortexm3_macro.h **** } + 106:stm32lib/inc/cortexm3_macro.h **** static inline void __DSB(void) { + 107:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "DSB \n" ); + 108:stm32lib/inc/cortexm3_macro.h **** } + 109:stm32lib/inc/cortexm3_macro.h **** static inline void __DMB(void) { + 110:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "DMB \n" ); + 111:stm32lib/inc/cortexm3_macro.h **** } + 112:stm32lib/inc/cortexm3_macro.h **** static inline void __SVC(void) { + 113:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "SVC 0x01 \n" ); + 114:stm32lib/inc/cortexm3_macro.h **** } + 115:stm32lib/inc/cortexm3_macro.h **** static inline u32 __MRS_CONTROL(void) { + 116:stm32lib/inc/cortexm3_macro.h **** u32 x; + 117:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "MRS %0, control \n" : "=r" (x)); + 118:stm32lib/inc/cortexm3_macro.h **** return x; + 119:stm32lib/inc/cortexm3_macro.h **** } + 120:stm32lib/inc/cortexm3_macro.h **** static inline void __MSR_CONTROL(u32 Control) { + 121:stm32lib/inc/cortexm3_macro.h **** asm volatile ( + 122:stm32lib/inc/cortexm3_macro.h **** "MSR control, %0 \n" + 123:stm32lib/inc/cortexm3_macro.h **** "ISB \n" + 124:stm32lib/inc/cortexm3_macro.h **** : : "r" (Control)); + 125:stm32lib/inc/cortexm3_macro.h **** } + 126:stm32lib/inc/cortexm3_macro.h **** static inline u32 __MRS_PSP(void) { + 127:stm32lib/inc/cortexm3_macro.h **** u32 x; + 128:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "MRS %0, psp \n" : "=r" (x)); + 129:stm32lib/inc/cortexm3_macro.h **** return x; + 130:stm32lib/inc/cortexm3_macro.h **** } + 131:stm32lib/inc/cortexm3_macro.h **** static inline void __MSR_PSP(u32 TopOfProcessStack) { + 132:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "MSR psp, %0 \n" : : "r" (TopOfProcessStack)); + 133:stm32lib/inc/cortexm3_macro.h **** } + 134:stm32lib/inc/cortexm3_macro.h **** static inline u32 __MRS_MSP(void) { + 135:stm32lib/inc/cortexm3_macro.h **** u32 x; + 136:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "MRS %0, msp \n" : "=r" (x)); + 137:stm32lib/inc/cortexm3_macro.h **** return x; + 138:stm32lib/inc/cortexm3_macro.h **** } + 139:stm32lib/inc/cortexm3_macro.h **** static inline void __MSR_MSP(u32 TopOfMainStack) { + 140:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "MSR msp, %0 \n" : : "r" (TopOfMainStack)); + 141:stm32lib/inc/cortexm3_macro.h **** } + 142:stm32lib/inc/cortexm3_macro.h **** static inline void __SETPRIMASK(void) { + 143:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "CPSID i \n" ); + 287 .loc 2 143 0 + 288 @ 143 "stm32lib/inc/cortexm3_macro.h" 1 + 289 0100 72B6 CPSID i + 290 + 291 @ 0 "" 2 + 292 .thumb + 293 .LBE5: + 294 .LBE4: + 186:stm32lib/src/stm32f10x_nvic.c **** __SETPRIMASK(); + 187:stm32lib/src/stm32f10x_nvic.c **** } + 295 .loc 1 187 0 + 296 0102 7047 bx lr + 297 .LFE28: + 299 .align 2 + 300 .global NVIC_RESETPRIMASK + 301 .thumb + 302 .thumb_func + 304 NVIC_RESETPRIMASK: + 305 .LFB29: + 188:stm32lib/src/stm32f10x_nvic.c **** + 189:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 190:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_RESETPRIMASK + 191:stm32lib/src/stm32f10x_nvic.c **** * Description : Disables the PRIMASK priority. + 192:stm32lib/src/stm32f10x_nvic.c **** * Input : None + 193:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 194:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 195:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 196:stm32lib/src/stm32f10x_nvic.c **** void NVIC_RESETPRIMASK(void) + 197:stm32lib/src/stm32f10x_nvic.c **** { + 306 .loc 1 197 0 + 307 @ args = 0, pretend = 0, frame = 0 + 308 @ frame_needed = 0, uses_anonymous_args = 0 + 309 @ link register save eliminated. + 310 .LBB8: + 311 .LBB9: + 144:stm32lib/inc/cortexm3_macro.h **** } + 145:stm32lib/inc/cortexm3_macro.h **** static inline void __RESETPRIMASK(void) { + 146:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "CPSIE i \n" ); + 312 .loc 2 146 0 + 313 @ 146 "stm32lib/inc/cortexm3_macro.h" 1 + 314 0104 62B6 CPSIE i + 315 + 316 @ 0 "" 2 + 317 .thumb + 318 .LBE9: + 319 .LBE8: + 198:stm32lib/src/stm32f10x_nvic.c **** __RESETPRIMASK(); + 199:stm32lib/src/stm32f10x_nvic.c **** } + 320 .loc 1 199 0 + 321 0106 7047 bx lr + 322 .LFE29: + 324 .align 2 + 325 .global NVIC_SETFAULTMASK + 326 .thumb + 327 .thumb_func + 329 NVIC_SETFAULTMASK: + 330 .LFB30: + 200:stm32lib/src/stm32f10x_nvic.c **** + 201:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 202:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_SETFAULTMASK + 203:stm32lib/src/stm32f10x_nvic.c **** * Description : Enables the FAULTMASK priority: Raises the execution priority to -1. + 204:stm32lib/src/stm32f10x_nvic.c **** * Input : None + 205:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 206:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 207:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 208:stm32lib/src/stm32f10x_nvic.c **** void NVIC_SETFAULTMASK(void) + 209:stm32lib/src/stm32f10x_nvic.c **** { + 331 .loc 1 209 0 + 332 @ args = 0, pretend = 0, frame = 0 + 333 @ frame_needed = 0, uses_anonymous_args = 0 + 334 @ link register save eliminated. + 335 .LBB12: + 336 .LBB13: + 147:stm32lib/inc/cortexm3_macro.h **** } + 148:stm32lib/inc/cortexm3_macro.h **** static inline void __SETFAULTMASK(void) { + 149:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "CPSID f \n" ); + 337 .loc 2 149 0 + 338 @ 149 "stm32lib/inc/cortexm3_macro.h" 1 + 339 0108 71B6 CPSID f + 340 + 341 @ 0 "" 2 + 342 .thumb + 343 .LBE13: + 344 .LBE12: + 210:stm32lib/src/stm32f10x_nvic.c **** __SETFAULTMASK(); + 211:stm32lib/src/stm32f10x_nvic.c **** } + 345 .loc 1 211 0 + 346 010a 7047 bx lr + 347 .LFE30: + 349 .align 2 + 350 .global NVIC_RESETFAULTMASK + 351 .thumb + 352 .thumb_func + 354 NVIC_RESETFAULTMASK: + 355 .LFB31: + 212:stm32lib/src/stm32f10x_nvic.c **** + 213:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 214:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_RESETFAULTMASK + 215:stm32lib/src/stm32f10x_nvic.c **** * Description : Disables the FAULTMASK priority. + 216:stm32lib/src/stm32f10x_nvic.c **** * Input : None + 217:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 218:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 219:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 220:stm32lib/src/stm32f10x_nvic.c **** void NVIC_RESETFAULTMASK(void) + 221:stm32lib/src/stm32f10x_nvic.c **** { + 356 .loc 1 221 0 + 357 @ args = 0, pretend = 0, frame = 0 + 358 @ frame_needed = 0, uses_anonymous_args = 0 + 359 @ link register save eliminated. + 360 .LBB16: + 361 .LBB17: + 150:stm32lib/inc/cortexm3_macro.h **** } + 151:stm32lib/inc/cortexm3_macro.h **** static inline void __RESETFAULTMASK(void) { + 152:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "CPSIE f \n" ); + 362 .loc 2 152 0 + 363 @ 152 "stm32lib/inc/cortexm3_macro.h" 1 + 364 010c 61B6 CPSIE f + 365 + 366 @ 0 "" 2 + 367 .thumb + 368 .LBE17: + 369 .LBE16: + 222:stm32lib/src/stm32f10x_nvic.c **** __RESETFAULTMASK(); + 223:stm32lib/src/stm32f10x_nvic.c **** } + 370 .loc 1 223 0 + 371 010e 7047 bx lr + 372 .LFE31: + 374 .align 2 + 375 .global NVIC_BASEPRICONFIG + 376 .thumb + 377 .thumb_func + 379 NVIC_BASEPRICONFIG: + 380 .LFB32: + 224:stm32lib/src/stm32f10x_nvic.c **** + 225:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 226:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_BASEPRICONFIG + 227:stm32lib/src/stm32f10x_nvic.c **** * Description : The execution priority can be changed from 15 (lowest + 228:stm32lib/src/stm32f10x_nvic.c **** configurable priority) to 1. Writing a zero value will disable + 229:stm32lib/src/stm32f10x_nvic.c **** * the mask of execution priority. + 230:stm32lib/src/stm32f10x_nvic.c **** * Input : None + 231:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 232:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 233:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 234:stm32lib/src/stm32f10x_nvic.c **** void NVIC_BASEPRICONFIG(u32 NewPriority) + 235:stm32lib/src/stm32f10x_nvic.c **** { + 381 .loc 1 235 0 + 382 @ args = 0, pretend = 0, frame = 0 + 383 @ frame_needed = 0, uses_anonymous_args = 0 + 384 @ link register save eliminated. + 385 .LVL19: + 386 .LBB20: + 387 .LBB21: + 153:stm32lib/inc/cortexm3_macro.h **** } + 154:stm32lib/inc/cortexm3_macro.h **** static inline void __BASEPRICONFIG(u32 NewPriority) { + 155:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "MSR basepri, %0 \n" : : "r" (NewPriority)); + 388 .loc 2 155 0 + 389 0110 0001 lsls r0, r0, #4 + 390 .LVL20: + 391 @ 155 "stm32lib/inc/cortexm3_macro.h" 1 + 392 0112 80F31188 MSR basepri, r0 + 393 + 394 @ 0 "" 2 + 395 .thumb + 396 .LBE21: + 397 .LBE20: + 236:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 237:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_NVIC_BASE_PRI(NewPriority)); + 238:stm32lib/src/stm32f10x_nvic.c **** + 239:stm32lib/src/stm32f10x_nvic.c **** __BASEPRICONFIG(NewPriority << 0x04); + 240:stm32lib/src/stm32f10x_nvic.c **** } + 398 .loc 1 240 0 + 399 0116 7047 bx lr + 400 .LFE32: + 402 .align 2 + 403 .global NVIC_GetBASEPRI + 404 .thumb + 405 .thumb_func + 407 NVIC_GetBASEPRI: + 408 .LFB33: + 241:stm32lib/src/stm32f10x_nvic.c **** + 242:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 243:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_GetBASEPRI + 244:stm32lib/src/stm32f10x_nvic.c **** * Description : Returns the BASEPRI mask value. + 245:stm32lib/src/stm32f10x_nvic.c **** * Input : None + 246:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 247:stm32lib/src/stm32f10x_nvic.c **** * Return : BASEPRI register value + 248:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 249:stm32lib/src/stm32f10x_nvic.c **** u32 NVIC_GetBASEPRI(void) + 250:stm32lib/src/stm32f10x_nvic.c **** { + 409 .loc 1 250 0 + 410 @ args = 0, pretend = 0, frame = 0 + 411 @ frame_needed = 0, uses_anonymous_args = 0 + 412 @ link register save eliminated. + 413 .LBB24: + 414 .LBB25: + 156:stm32lib/inc/cortexm3_macro.h **** } + 157:stm32lib/inc/cortexm3_macro.h **** static inline u32 __GetBASEPRI(void) { + 158:stm32lib/inc/cortexm3_macro.h **** u32 x; + 159:stm32lib/inc/cortexm3_macro.h **** asm volatile ( "MRS %0, basepri_max \n" : "=r" (x)); + 415 .loc 2 159 0 + 416 @ 159 "stm32lib/inc/cortexm3_macro.h" 1 + 417 0118 EFF31280 MRS r0, basepri_max + 418 + 419 @ 0 "" 2 + 420 .LVL21: + 421 .LVL22: + 422 .thumb + 423 .LBE25: + 424 .LBE24: + 251:stm32lib/src/stm32f10x_nvic.c **** return (__GetBASEPRI()); + 252:stm32lib/src/stm32f10x_nvic.c **** } + 425 .loc 1 252 0 + 426 011c 7047 bx lr + 427 .LFE33: + 429 011e 00BF .align 2 + 430 .global NVIC_GetCurrentPendingIRQChannel + 431 .thumb + 432 .thumb_func + 434 NVIC_GetCurrentPendingIRQChannel: + 435 .LFB34: + 253:stm32lib/src/stm32f10x_nvic.c **** + 254:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 255:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_GetCurrentPendingIRQChannel + 256:stm32lib/src/stm32f10x_nvic.c **** * Description : Returns the current pending IRQ channel identifier. + 257:stm32lib/src/stm32f10x_nvic.c **** * Input : None + 258:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 259:stm32lib/src/stm32f10x_nvic.c **** * Return : Pending IRQ Channel Identifier. + 260:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 261:stm32lib/src/stm32f10x_nvic.c **** u16 NVIC_GetCurrentPendingIRQChannel(void) + 262:stm32lib/src/stm32f10x_nvic.c **** { + 436 .loc 1 262 0 + 437 @ args = 0, pretend = 0, frame = 0 + 438 @ frame_needed = 0, uses_anonymous_args = 0 + 439 @ link register save eliminated. + 263:stm32lib/src/stm32f10x_nvic.c **** return ((u16)((SCB->ICSR & (u32)0x003FF000) >> 0x0C)); + 440 .loc 1 263 0 + 441 0120 024B ldr r3, .L36 + 442 0122 5868 ldr r0, [r3, #4] + 264:stm32lib/src/stm32f10x_nvic.c **** } + 443 .loc 1 264 0 + 444 0124 C0F30930 ubfx r0, r0, #12, #10 + 445 0128 7047 bx lr + 446 .L37: + 447 012a 00BF .align 2 + 448 .L36: + 449 012c 00ED00E0 .word -536810240 + 450 .LFE34: + 452 .align 2 + 453 .global NVIC_GetIRQChannelPendingBitStatus + 454 .thumb + 455 .thumb_func + 457 NVIC_GetIRQChannelPendingBitStatus: + 458 .LFB35: + 265:stm32lib/src/stm32f10x_nvic.c **** + 266:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 267:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_GetIRQChannelPendingBitStatus + 268:stm32lib/src/stm32f10x_nvic.c **** * Description : Checks whether the specified IRQ Channel pending bit is set + 269:stm32lib/src/stm32f10x_nvic.c **** * or not. + 270:stm32lib/src/stm32f10x_nvic.c **** * Input : - NVIC_IRQChannel: specifies the interrupt pending bit to check. + 271:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 272:stm32lib/src/stm32f10x_nvic.c **** * Return : The new state of IRQ Channel pending bit(SET or RESET). + 273:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 274:stm32lib/src/stm32f10x_nvic.c **** ITStatus NVIC_GetIRQChannelPendingBitStatus(u8 NVIC_IRQChannel) + 275:stm32lib/src/stm32f10x_nvic.c **** { + 459 .loc 1 275 0 + 460 @ args = 0, pretend = 0, frame = 0 + 461 @ frame_needed = 0, uses_anonymous_args = 0 + 462 @ link register save eliminated. + 463 .LVL23: + 276:stm32lib/src/stm32f10x_nvic.c **** ITStatus pendingirqstatus = RESET; + 277:stm32lib/src/stm32f10x_nvic.c **** u32 tmp = 0x00; + 278:stm32lib/src/stm32f10x_nvic.c **** + 279:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 280:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_IRQChannel)); + 281:stm32lib/src/stm32f10x_nvic.c **** + 282:stm32lib/src/stm32f10x_nvic.c **** tmp = ((u32)0x01 << (NVIC_IRQChannel & (u32)0x1F)); + 464 .loc 1 282 0 + 465 0130 00F01F03 and r3, r0, #31 + 466 0134 0122 movs r2, #1 + 467 0136 9A40 lsls r2, r2, r3 + 468 .LVL24: + 283:stm32lib/src/stm32f10x_nvic.c **** + 284:stm32lib/src/stm32f10x_nvic.c **** if (((NVIC->ISPR[(NVIC_IRQChannel >> 0x05)]) & tmp) == tmp) + 469 .loc 1 284 0 + 470 0138 4009 lsrs r0, r0, #5 + 471 .LVL25: + 472 013a 054B ldr r3, .L40 + 473 013c 4030 adds r0, r0, #64 + 474 013e 53F82000 ldr r0, [r3, r0, lsl #2] + 475 0142 1040 ands r0, r0, r2 + 285:stm32lib/src/stm32f10x_nvic.c **** { + 286:stm32lib/src/stm32f10x_nvic.c **** pendingirqstatus = SET; + 287:stm32lib/src/stm32f10x_nvic.c **** } + 288:stm32lib/src/stm32f10x_nvic.c **** else + 289:stm32lib/src/stm32f10x_nvic.c **** { + 290:stm32lib/src/stm32f10x_nvic.c **** pendingirqstatus = RESET; + 291:stm32lib/src/stm32f10x_nvic.c **** } + 292:stm32lib/src/stm32f10x_nvic.c **** return pendingirqstatus; + 293:stm32lib/src/stm32f10x_nvic.c **** } + 476 .loc 1 293 0 + 477 0144 9042 cmp r0, r2 + 478 0146 14BF ite ne + 479 0148 0020 movne r0, #0 + 480 014a 0120 moveq r0, #1 + 481 014c 7047 bx lr + 482 .L41: + 483 014e 00BF .align 2 + 484 .L40: + 485 0150 00E100E0 .word -536813312 + 486 .LFE35: + 488 .align 2 + 489 .global NVIC_SetIRQChannelPendingBit + 490 .thumb + 491 .thumb_func + 493 NVIC_SetIRQChannelPendingBit: + 494 .LFB36: + 294:stm32lib/src/stm32f10x_nvic.c **** + 295:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 296:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_SetIRQChannelPendingBit + 297:stm32lib/src/stm32f10x_nvic.c **** * Description : Sets the NVIC’s interrupt pending bit. + 298:stm32lib/src/stm32f10x_nvic.c **** * Input : - NVIC_IRQChannel: specifies the interrupt pending bit to Set. + 299:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 300:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 301:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 302:stm32lib/src/stm32f10x_nvic.c **** void NVIC_SetIRQChannelPendingBit(u8 NVIC_IRQChannel) + 303:stm32lib/src/stm32f10x_nvic.c **** { + 495 .loc 1 303 0 + 496 @ args = 0, pretend = 0, frame = 0 + 497 @ frame_needed = 0, uses_anonymous_args = 0 + 498 @ link register save eliminated. + 499 .LVL26: + 304:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 305:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_IRQChannel)); + 306:stm32lib/src/stm32f10x_nvic.c **** + 307:stm32lib/src/stm32f10x_nvic.c **** *(vu32*) 0xE000EF00 = (u32)NVIC_IRQChannel; + 500 .loc 1 307 0 + 501 0154 014B ldr r3, .L44 + 502 0156 1860 str r0, [r3, #0] + 308:stm32lib/src/stm32f10x_nvic.c **** } + 503 .loc 1 308 0 + 504 0158 7047 bx lr + 505 .L45: + 506 015a 00BF .align 2 + 507 .L44: + 508 015c 00EF00E0 .word -536809728 + 509 .LFE36: + 511 .align 2 + 512 .global NVIC_ClearIRQChannelPendingBit + 513 .thumb + 514 .thumb_func + 516 NVIC_ClearIRQChannelPendingBit: + 517 .LFB37: + 309:stm32lib/src/stm32f10x_nvic.c **** + 310:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 311:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_ClearIRQChannelPendingBit + 312:stm32lib/src/stm32f10x_nvic.c **** * Description : Clears the NVIC’s interrupt pending bit. + 313:stm32lib/src/stm32f10x_nvic.c **** * Input : - NVIC_IRQChannel: specifies the interrupt pending bit to clear. + 314:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 315:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 316:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 317:stm32lib/src/stm32f10x_nvic.c **** void NVIC_ClearIRQChannelPendingBit(u8 NVIC_IRQChannel) + 318:stm32lib/src/stm32f10x_nvic.c **** { + 518 .loc 1 318 0 + 519 @ args = 0, pretend = 0, frame = 0 + 520 @ frame_needed = 0, uses_anonymous_args = 0 + 521 @ link register save eliminated. + 522 .LVL27: + 319:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 320:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_IRQChannel)); + 321:stm32lib/src/stm32f10x_nvic.c **** + 322:stm32lib/src/stm32f10x_nvic.c **** NVIC->ICPR[(NVIC_IRQChannel >> 0x05)] = (u32)0x01 << (NVIC_IRQChannel & (u32)0x1F); + 523 .loc 1 322 0 + 524 0160 4109 lsrs r1, r0, #5 + 525 0162 0123 movs r3, #1 + 526 0164 00F01F00 and r0, r0, #31 + 527 .LVL28: + 528 0168 8340 lsls r3, r3, r0 + 529 016a 024A ldr r2, .L48 + 530 016c 6031 adds r1, r1, #96 + 531 016e 42F82130 str r3, [r2, r1, lsl #2] + 323:stm32lib/src/stm32f10x_nvic.c **** } + 532 .loc 1 323 0 + 533 0172 7047 bx lr + 534 .L49: + 535 .align 2 + 536 .L48: + 537 0174 00E100E0 .word -536813312 + 538 .LFE37: + 540 .align 2 + 541 .global NVIC_GetCurrentActiveHandler + 542 .thumb + 543 .thumb_func + 545 NVIC_GetCurrentActiveHandler: + 546 .LFB38: + 324:stm32lib/src/stm32f10x_nvic.c **** + 325:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 326:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_GetCurrentActiveHandler + 327:stm32lib/src/stm32f10x_nvic.c **** * Description : Returns the current active Handler (IRQ Channel and + 328:stm32lib/src/stm32f10x_nvic.c **** * SystemHandler) identifier. + 329:stm32lib/src/stm32f10x_nvic.c **** * Input : None + 330:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 331:stm32lib/src/stm32f10x_nvic.c **** * Return : Active Handler Identifier. + 332:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 333:stm32lib/src/stm32f10x_nvic.c **** u16 NVIC_GetCurrentActiveHandler(void) + 334:stm32lib/src/stm32f10x_nvic.c **** { + 547 .loc 1 334 0 + 548 @ args = 0, pretend = 0, frame = 0 + 549 @ frame_needed = 0, uses_anonymous_args = 0 + 550 @ link register save eliminated. + 335:stm32lib/src/stm32f10x_nvic.c **** return ((u16)(SCB->ICSR & (u32)0x3FF)); + 551 .loc 1 335 0 + 552 0178 024B ldr r3, .L52 + 553 017a 5868 ldr r0, [r3, #4] + 336:stm32lib/src/stm32f10x_nvic.c **** } + 554 .loc 1 336 0 + 555 017c 8005 lsls r0, r0, #22 + 556 017e 800D lsrs r0, r0, #22 + 557 0180 7047 bx lr + 558 .L53: + 559 0182 00BF .align 2 + 560 .L52: + 561 0184 00ED00E0 .word -536810240 + 562 .LFE38: + 564 .align 2 + 565 .global NVIC_GetIRQChannelActiveBitStatus + 566 .thumb + 567 .thumb_func + 569 NVIC_GetIRQChannelActiveBitStatus: + 570 .LFB39: + 337:stm32lib/src/stm32f10x_nvic.c **** + 338:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 339:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_GetIRQChannelActiveBitStatus + 340:stm32lib/src/stm32f10x_nvic.c **** * Description : Checks whether the specified IRQ Channel active bit is set + 341:stm32lib/src/stm32f10x_nvic.c **** * or not. + 342:stm32lib/src/stm32f10x_nvic.c **** * Input : - NVIC_IRQChannel: specifies the interrupt active bit to check. + 343:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 344:stm32lib/src/stm32f10x_nvic.c **** * Return : The new state of IRQ Channel active bit(SET or RESET). + 345:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 346:stm32lib/src/stm32f10x_nvic.c **** ITStatus NVIC_GetIRQChannelActiveBitStatus(u8 NVIC_IRQChannel) + 347:stm32lib/src/stm32f10x_nvic.c **** { + 571 .loc 1 347 0 + 572 @ args = 0, pretend = 0, frame = 0 + 573 @ frame_needed = 0, uses_anonymous_args = 0 + 574 @ link register save eliminated. + 575 .LVL29: + 348:stm32lib/src/stm32f10x_nvic.c **** ITStatus activeirqstatus = RESET; + 349:stm32lib/src/stm32f10x_nvic.c **** u32 tmp = 0x00; + 350:stm32lib/src/stm32f10x_nvic.c **** + 351:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 352:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_NVIC_IRQ_CHANNEL(NVIC_IRQChannel)); + 353:stm32lib/src/stm32f10x_nvic.c **** + 354:stm32lib/src/stm32f10x_nvic.c **** tmp = ((u32)0x01 << (NVIC_IRQChannel & (u32)0x1F)); + 576 .loc 1 354 0 + 577 0188 00F01F03 and r3, r0, #31 + 578 018c 0122 movs r2, #1 + 579 018e 9A40 lsls r2, r2, r3 + 580 .LVL30: + 355:stm32lib/src/stm32f10x_nvic.c **** + 356:stm32lib/src/stm32f10x_nvic.c **** if (((NVIC->IABR[(NVIC_IRQChannel >> 0x05)]) & tmp) == tmp ) + 581 .loc 1 356 0 + 582 0190 4009 lsrs r0, r0, #5 + 583 .LVL31: + 584 0192 054B ldr r3, .L56 + 585 0194 8030 adds r0, r0, #128 + 586 0196 53F82000 ldr r0, [r3, r0, lsl #2] + 587 019a 1040 ands r0, r0, r2 + 357:stm32lib/src/stm32f10x_nvic.c **** { + 358:stm32lib/src/stm32f10x_nvic.c **** activeirqstatus = SET; + 359:stm32lib/src/stm32f10x_nvic.c **** } + 360:stm32lib/src/stm32f10x_nvic.c **** else + 361:stm32lib/src/stm32f10x_nvic.c **** { + 362:stm32lib/src/stm32f10x_nvic.c **** activeirqstatus = RESET; + 363:stm32lib/src/stm32f10x_nvic.c **** } + 364:stm32lib/src/stm32f10x_nvic.c **** return activeirqstatus; + 365:stm32lib/src/stm32f10x_nvic.c **** } + 588 .loc 1 365 0 + 589 019c 9042 cmp r0, r2 + 590 019e 14BF ite ne + 591 01a0 0020 movne r0, #0 + 592 01a2 0120 moveq r0, #1 + 593 01a4 7047 bx lr + 594 .L57: + 595 01a6 00BF .align 2 + 596 .L56: + 597 01a8 00E100E0 .word -536813312 + 598 .LFE39: + 600 .align 2 + 601 .global NVIC_GetCPUID + 602 .thumb + 603 .thumb_func + 605 NVIC_GetCPUID: + 606 .LFB40: + 366:stm32lib/src/stm32f10x_nvic.c **** + 367:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 368:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_GetCPUID + 369:stm32lib/src/stm32f10x_nvic.c **** * Description : Returns the ID number, the version number and the implementation + 370:stm32lib/src/stm32f10x_nvic.c **** * details of the Cortex-M3 core. + 371:stm32lib/src/stm32f10x_nvic.c **** * Input : None + 372:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 373:stm32lib/src/stm32f10x_nvic.c **** * Return : CPU ID. + 374:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 375:stm32lib/src/stm32f10x_nvic.c **** u32 NVIC_GetCPUID(void) + 376:stm32lib/src/stm32f10x_nvic.c **** { + 607 .loc 1 376 0 + 608 @ args = 0, pretend = 0, frame = 0 + 609 @ frame_needed = 0, uses_anonymous_args = 0 + 610 @ link register save eliminated. + 377:stm32lib/src/stm32f10x_nvic.c **** return (SCB->CPUID); + 611 .loc 1 377 0 + 612 01ac 014B ldr r3, .L60 + 613 01ae 1868 ldr r0, [r3, #0] + 378:stm32lib/src/stm32f10x_nvic.c **** } + 614 .loc 1 378 0 + 615 01b0 7047 bx lr + 616 .L61: + 617 01b2 00BF .align 2 + 618 .L60: + 619 01b4 00ED00E0 .word -536810240 + 620 .LFE40: + 622 .align 2 + 623 .global NVIC_SetVectorTable + 624 .thumb + 625 .thumb_func + 627 NVIC_SetVectorTable: + 628 .LFB41: + 379:stm32lib/src/stm32f10x_nvic.c **** + 380:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 381:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_SetVectorTable + 382:stm32lib/src/stm32f10x_nvic.c **** * Description : Sets the vector table location and Offset. + 383:stm32lib/src/stm32f10x_nvic.c **** * Input : - NVIC_VectTab: specifies if the vector table is in RAM or + 384:stm32lib/src/stm32f10x_nvic.c **** * FLASH memory. + 385:stm32lib/src/stm32f10x_nvic.c **** * This parameter can be one of the following values: + 386:stm32lib/src/stm32f10x_nvic.c **** * - NVIC_VectTab_RAM + 387:stm32lib/src/stm32f10x_nvic.c **** * - NVIC_VectTab_FLASH + 388:stm32lib/src/stm32f10x_nvic.c **** * - Offset: Vector Table base offset field. + 389:stm32lib/src/stm32f10x_nvic.c **** * This value must be a multiple of 0x100. + 390:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 391:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 392:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 393:stm32lib/src/stm32f10x_nvic.c **** void NVIC_SetVectorTable(u32 NVIC_VectTab, u32 Offset) + 394:stm32lib/src/stm32f10x_nvic.c **** { + 629 .loc 1 394 0 + 630 @ args = 0, pretend = 0, frame = 0 + 631 @ frame_needed = 0, uses_anonymous_args = 0 + 632 @ link register save eliminated. + 633 .LVL32: + 395:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 396:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_NVIC_VECTTAB(NVIC_VectTab)); + 397:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_NVIC_OFFSET(Offset)); + 398:stm32lib/src/stm32f10x_nvic.c **** + 399:stm32lib/src/stm32f10x_nvic.c **** SCB->VTOR = NVIC_VectTab | (Offset & (u32)0x1FFFFF80); + 634 .loc 1 399 0 + 635 01b8 21F06041 bic r1, r1, #-536870912 + 636 .LVL33: + 637 01bc 21F07F01 bic r1, r1, #127 + 638 01c0 014B ldr r3, .L64 + 639 01c2 0143 orrs r1, r1, r0 + 640 01c4 9960 str r1, [r3, #8] + 400:stm32lib/src/stm32f10x_nvic.c **** } + 641 .loc 1 400 0 + 642 01c6 7047 bx lr + 643 .L65: + 644 .align 2 + 645 .L64: + 646 01c8 00ED00E0 .word -536810240 + 647 .LFE41: + 649 .align 2 + 650 .global NVIC_GenerateSystemReset + 651 .thumb + 652 .thumb_func + 654 NVIC_GenerateSystemReset: + 655 .LFB42: + 401:stm32lib/src/stm32f10x_nvic.c **** + 402:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 403:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_GenerateSystemReset + 404:stm32lib/src/stm32f10x_nvic.c **** * Description : Generates a system reset. + 405:stm32lib/src/stm32f10x_nvic.c **** * Input : None + 406:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 407:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 408:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 409:stm32lib/src/stm32f10x_nvic.c **** void NVIC_GenerateSystemReset(void) + 410:stm32lib/src/stm32f10x_nvic.c **** { + 656 .loc 1 410 0 + 657 @ args = 0, pretend = 0, frame = 0 + 658 @ frame_needed = 0, uses_anonymous_args = 0 + 659 @ link register save eliminated. + 411:stm32lib/src/stm32f10x_nvic.c **** SCB->AIRCR = AIRCR_VECTKEY_MASK | (u32)0x04; + 660 .loc 1 411 0 + 661 01cc 014A ldr r2, .L68 + 662 01ce 024B ldr r3, .L68+4 + 663 01d0 DA60 str r2, [r3, #12] + 412:stm32lib/src/stm32f10x_nvic.c **** } + 664 .loc 1 412 0 + 665 01d2 7047 bx lr + 666 .L69: + 667 .align 2 + 668 .L68: + 669 01d4 0400FA05 .word 100270084 + 670 01d8 00ED00E0 .word -536810240 + 671 .LFE42: + 673 .align 2 + 674 .global NVIC_GenerateCoreReset + 675 .thumb + 676 .thumb_func + 678 NVIC_GenerateCoreReset: + 679 .LFB43: + 413:stm32lib/src/stm32f10x_nvic.c **** + 414:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 415:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_GenerateCoreReset + 416:stm32lib/src/stm32f10x_nvic.c **** * Description : Generates a Core (Core + NVIC) reset. + 417:stm32lib/src/stm32f10x_nvic.c **** * Input : None + 418:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 419:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 420:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 421:stm32lib/src/stm32f10x_nvic.c **** void NVIC_GenerateCoreReset(void) + 422:stm32lib/src/stm32f10x_nvic.c **** { + 680 .loc 1 422 0 + 681 @ args = 0, pretend = 0, frame = 0 + 682 @ frame_needed = 0, uses_anonymous_args = 0 + 683 @ link register save eliminated. + 423:stm32lib/src/stm32f10x_nvic.c **** SCB->AIRCR = AIRCR_VECTKEY_MASK | (u32)0x01; + 684 .loc 1 423 0 + 685 01dc 014A ldr r2, .L72 + 686 01de 024B ldr r3, .L72+4 + 687 01e0 DA60 str r2, [r3, #12] + 424:stm32lib/src/stm32f10x_nvic.c **** } + 688 .loc 1 424 0 + 689 01e2 7047 bx lr + 690 .L73: + 691 .align 2 + 692 .L72: + 693 01e4 0100FA05 .word 100270081 + 694 01e8 00ED00E0 .word -536810240 + 695 .LFE43: + 697 .align 2 + 698 .global NVIC_SystemLPConfig + 699 .thumb + 700 .thumb_func + 702 NVIC_SystemLPConfig: + 703 .LFB44: + 425:stm32lib/src/stm32f10x_nvic.c **** + 426:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 427:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_SystemLPConfig + 428:stm32lib/src/stm32f10x_nvic.c **** * Description : Selects the condition for the system to enter low power mode. + 429:stm32lib/src/stm32f10x_nvic.c **** * Input : - LowPowerMode: Specifies the new mode for the system to enter + 430:stm32lib/src/stm32f10x_nvic.c **** * low power mode. + 431:stm32lib/src/stm32f10x_nvic.c **** * This parameter can be one of the following values: + 432:stm32lib/src/stm32f10x_nvic.c **** * - NVIC_LP_SEVONPEND + 433:stm32lib/src/stm32f10x_nvic.c **** * - NVIC_LP_SLEEPDEEP + 434:stm32lib/src/stm32f10x_nvic.c **** * - NVIC_LP_SLEEPONEXIT + 435:stm32lib/src/stm32f10x_nvic.c **** * - NewState: new state of LP condition. + 436:stm32lib/src/stm32f10x_nvic.c **** * This parameter can be: ENABLE or DISABLE. + 437:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 438:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 439:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 440:stm32lib/src/stm32f10x_nvic.c **** void NVIC_SystemLPConfig(u8 LowPowerMode, FunctionalState NewState) + 441:stm32lib/src/stm32f10x_nvic.c **** { + 704 .loc 1 441 0 + 705 @ args = 0, pretend = 0, frame = 0 + 706 @ frame_needed = 0, uses_anonymous_args = 0 + 707 @ link register save eliminated. + 708 .LVL34: + 442:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 443:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_NVIC_LP(LowPowerMode)); + 444:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 445:stm32lib/src/stm32f10x_nvic.c **** + 446:stm32lib/src/stm32f10x_nvic.c **** if (NewState != DISABLE) + 709 .loc 1 446 0 + 710 01ec 21B1 cbz r1, .L75 + 447:stm32lib/src/stm32f10x_nvic.c **** { + 448:stm32lib/src/stm32f10x_nvic.c **** SCB->SCR |= LowPowerMode; + 711 .loc 1 448 0 + 712 01ee 054A ldr r2, .L79 + 713 01f0 1369 ldr r3, [r2, #16] + 714 01f2 40EA0303 orr r3, r0, r3 + 715 01f6 03E0 b .L78 + 716 .L75: + 449:stm32lib/src/stm32f10x_nvic.c **** } + 450:stm32lib/src/stm32f10x_nvic.c **** else + 451:stm32lib/src/stm32f10x_nvic.c **** { + 452:stm32lib/src/stm32f10x_nvic.c **** SCB->SCR &= (u32)(~(u32)LowPowerMode); + 717 .loc 1 452 0 + 718 01f8 024A ldr r2, .L79 + 719 01fa 1369 ldr r3, [r2, #16] + 720 01fc 23EA0003 bic r3, r3, r0 + 721 .L78: + 722 0200 1361 str r3, [r2, #16] + 453:stm32lib/src/stm32f10x_nvic.c **** } + 454:stm32lib/src/stm32f10x_nvic.c **** } + 723 .loc 1 454 0 + 724 0202 7047 bx lr + 725 .L80: + 726 .align 2 + 727 .L79: + 728 0204 00ED00E0 .word -536810240 + 729 .LFE44: + 731 .align 2 + 732 .global NVIC_SystemHandlerConfig + 733 .thumb + 734 .thumb_func + 736 NVIC_SystemHandlerConfig: + 737 .LFB45: + 455:stm32lib/src/stm32f10x_nvic.c **** + 456:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 457:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_SystemHandlerConfig + 458:stm32lib/src/stm32f10x_nvic.c **** * Description : Enables or disables the specified System Handlers. + 459:stm32lib/src/stm32f10x_nvic.c **** * Input : - SystemHandler: specifies the system handler to be enabled + 460:stm32lib/src/stm32f10x_nvic.c **** * or disabled. + 461:stm32lib/src/stm32f10x_nvic.c **** * This parameter can be one of the following values: + 462:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_MemoryManage + 463:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_BusFault + 464:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_UsageFault + 465:stm32lib/src/stm32f10x_nvic.c **** * - NewState: new state of specified System Handlers. + 466:stm32lib/src/stm32f10x_nvic.c **** * This parameter can be: ENABLE or DISABLE. + 467:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 468:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 469:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 470:stm32lib/src/stm32f10x_nvic.c **** void NVIC_SystemHandlerConfig(u32 SystemHandler, FunctionalState NewState) + 471:stm32lib/src/stm32f10x_nvic.c **** { + 738 .loc 1 471 0 + 739 @ args = 0, pretend = 0, frame = 0 + 740 @ frame_needed = 0, uses_anonymous_args = 0 + 741 @ link register save eliminated. + 742 .LVL35: + 472:stm32lib/src/stm32f10x_nvic.c **** u32 tmpreg = 0x00; + 473:stm32lib/src/stm32f10x_nvic.c **** + 474:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 475:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_CONFIG_SYSTEM_HANDLER(SystemHandler)); + 476:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 477:stm32lib/src/stm32f10x_nvic.c **** + 478:stm32lib/src/stm32f10x_nvic.c **** tmpreg = (u32)0x01 << (SystemHandler & (u32)0x1F); + 743 .loc 1 478 0 + 744 0208 00F01F00 and r0, r0, #31 + 745 .LVL36: + 746 020c 0123 movs r3, #1 + 747 020e 13FA00F0 lsls r0, r3, r0 + 748 .LVL37: + 479:stm32lib/src/stm32f10x_nvic.c **** + 480:stm32lib/src/stm32f10x_nvic.c **** if (NewState != DISABLE) + 749 .loc 1 480 0 + 750 0212 21B1 cbz r1, .L82 + 481:stm32lib/src/stm32f10x_nvic.c **** { + 482:stm32lib/src/stm32f10x_nvic.c **** SCB->SHCSR |= tmpreg; + 751 .loc 1 482 0 + 752 0214 054A ldr r2, .L86 + 753 0216 536A ldr r3, [r2, #36] + 754 0218 40EA0303 orr r3, r0, r3 + 755 021c 03E0 b .L85 + 756 .L82: + 483:stm32lib/src/stm32f10x_nvic.c **** } + 484:stm32lib/src/stm32f10x_nvic.c **** else + 485:stm32lib/src/stm32f10x_nvic.c **** { + 486:stm32lib/src/stm32f10x_nvic.c **** SCB->SHCSR &= ~tmpreg; + 757 .loc 1 486 0 + 758 021e 034A ldr r2, .L86 + 759 0220 536A ldr r3, [r2, #36] + 760 0222 23EA0003 bic r3, r3, r0 + 761 .L85: + 762 0226 5362 str r3, [r2, #36] + 487:stm32lib/src/stm32f10x_nvic.c **** } + 488:stm32lib/src/stm32f10x_nvic.c **** } + 763 .loc 1 488 0 + 764 0228 7047 bx lr + 765 .L87: + 766 022a 00BF .align 2 + 767 .L86: + 768 022c 00ED00E0 .word -536810240 + 769 .LFE45: + 771 .align 2 + 772 .global NVIC_SystemHandlerPriorityConfig + 773 .thumb + 774 .thumb_func + 776 NVIC_SystemHandlerPriorityConfig: + 777 .LFB46: + 489:stm32lib/src/stm32f10x_nvic.c **** + 490:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 491:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_SystemHandlerPriorityConfig + 492:stm32lib/src/stm32f10x_nvic.c **** * Description : Configures the specified System Handlers priority. + 493:stm32lib/src/stm32f10x_nvic.c **** * Input : - SystemHandler: specifies the system handler to be + 494:stm32lib/src/stm32f10x_nvic.c **** * enabled or disabled. + 495:stm32lib/src/stm32f10x_nvic.c **** * This parameter can be one of the following values: + 496:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_MemoryManage + 497:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_BusFault + 498:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_UsageFault + 499:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_SVCall + 500:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_DebugMonitor + 501:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_PSV + 502:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_SysTick + 503:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandlerPreemptionPriority: new priority group of the + 504:stm32lib/src/stm32f10x_nvic.c **** * specified system handlers. + 505:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandlerSubPriority: new sub priority of the specified + 506:stm32lib/src/stm32f10x_nvic.c **** * system handlers. + 507:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 508:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 509:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 510:stm32lib/src/stm32f10x_nvic.c **** void NVIC_SystemHandlerPriorityConfig(u32 SystemHandler, u8 SystemHandlerPreemptionPriority, + 511:stm32lib/src/stm32f10x_nvic.c **** u8 SystemHandlerSubPriority) + 512:stm32lib/src/stm32f10x_nvic.c **** { + 778 .loc 1 512 0 + 779 @ args = 0, pretend = 0, frame = 0 + 780 @ frame_needed = 0, uses_anonymous_args = 0 + 781 .LVL38: + 782 0230 30B5 push {r4, r5, lr} + 783 .LCFI1: + 513:stm32lib/src/stm32f10x_nvic.c **** u32 tmp1 = 0x00, tmp2 = 0xFF, handlermask = 0x00; + 514:stm32lib/src/stm32f10x_nvic.c **** u32 tmppriority = 0x00; + 515:stm32lib/src/stm32f10x_nvic.c **** + 516:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 517:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_PRIORITY_SYSTEM_HANDLER(SystemHandler)); + 518:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_NVIC_PREEMPTION_PRIORITY(SystemHandlerPreemptionPriority)); + 519:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_NVIC_SUB_PRIORITY(SystemHandlerSubPriority)); + 520:stm32lib/src/stm32f10x_nvic.c **** + 521:stm32lib/src/stm32f10x_nvic.c **** tmppriority = (0x700 - (SCB->AIRCR & (u32)0x700))>> 0x08; + 784 .loc 1 521 0 + 785 0232 114D ldr r5, .L90 + 786 0234 EB68 ldr r3, [r5, #12] + 787 0236 DB43 mvns r3, r3 + 788 0238 C3F30223 ubfx r3, r3, #8, #3 + 789 .LVL39: + 522:stm32lib/src/stm32f10x_nvic.c **** tmp1 = (0x4 - tmppriority); + 523:stm32lib/src/stm32f10x_nvic.c **** tmp2 = tmp2 >> tmppriority; + 524:stm32lib/src/stm32f10x_nvic.c **** + 525:stm32lib/src/stm32f10x_nvic.c **** tmppriority = (u32)SystemHandlerPreemptionPriority << tmp1; + 790 .loc 1 525 0 + 791 023c C3F10404 rsb r4, r3, #4 + 792 0240 A140 lsls r1, r1, r4 + 793 .LVL40: + 526:stm32lib/src/stm32f10x_nvic.c **** tmppriority |= SystemHandlerSubPriority & tmp2; + 794 .loc 1 526 0 + 795 0242 FF24 movs r4, #255 + 796 0244 34FA03F3 lsrs r3, r4, r3 + 797 0248 1A40 ands r2, r2, r3 + 798 .LVL41: + 799 024a 0A43 orrs r2, r2, r1 + 800 .LVL42: + 527:stm32lib/src/stm32f10x_nvic.c **** + 528:stm32lib/src/stm32f10x_nvic.c **** tmppriority = tmppriority << 0x04; + 529:stm32lib/src/stm32f10x_nvic.c **** tmp1 = SystemHandler & (u32)0xC0; + 530:stm32lib/src/stm32f10x_nvic.c **** tmp1 = tmp1 >> 0x06; + 801 .loc 1 530 0 + 802 024c C0F38111 ubfx r1, r0, #6, #2 + 803 .LVL43: + 531:stm32lib/src/stm32f10x_nvic.c **** tmp2 = (SystemHandler >> 0x08) & (u32)0x03; + 532:stm32lib/src/stm32f10x_nvic.c **** tmppriority = tmppriority << (tmp2 * 0x08); + 804 .loc 1 532 0 + 805 0250 C0F30120 ubfx r0, r0, #8, #2 + 806 .LVL44: + 807 0254 C000 lsls r0, r0, #3 + 533:stm32lib/src/stm32f10x_nvic.c **** handlermask = (u32)0xFF << (tmp2 * 0x08); + 534:stm32lib/src/stm32f10x_nvic.c **** + 535:stm32lib/src/stm32f10x_nvic.c **** SCB->SHPR[tmp1] &= ~handlermask; + 808 .loc 1 535 0 + 809 0256 8440 lsls r4, r4, r0 + 810 .loc 1 528 0 + 811 0258 1201 lsls r2, r2, #4 + 812 .LVL45: + 536:stm32lib/src/stm32f10x_nvic.c **** SCB->SHPR[tmp1] |= tmppriority; + 813 .loc 1 536 0 + 814 025a 8240 lsls r2, r2, r0 + 815 .LVL46: + 816 .loc 1 535 0 + 817 025c 0631 adds r1, r1, #6 + 818 .LVL47: + 819 025e 55F82130 ldr r3, [r5, r1, lsl #2] + 820 0262 23EA0403 bic r3, r3, r4 + 821 0266 45F82130 str r3, [r5, r1, lsl #2] + 822 .loc 1 536 0 + 823 026a 55F82130 ldr r3, [r5, r1, lsl #2] + 824 026e 1A43 orrs r2, r2, r3 + 825 0270 45F82120 str r2, [r5, r1, lsl #2] + 537:stm32lib/src/stm32f10x_nvic.c **** } + 826 .loc 1 537 0 + 827 0274 30BD pop {r4, r5, pc} + 828 .L91: + 829 0276 00BF .align 2 + 830 .L90: + 831 0278 00ED00E0 .word -536810240 + 832 .LFE46: + 834 .align 2 + 835 .global NVIC_GetSystemHandlerPendingBitStatus + 836 .thumb + 837 .thumb_func + 839 NVIC_GetSystemHandlerPendingBitStatus: + 840 .LFB47: + 538:stm32lib/src/stm32f10x_nvic.c **** + 539:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 540:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_GetSystemHandlerPendingBitStatus + 541:stm32lib/src/stm32f10x_nvic.c **** * Description : Checks whether the specified System handlers pending bit is + 542:stm32lib/src/stm32f10x_nvic.c **** * set or not. + 543:stm32lib/src/stm32f10x_nvic.c **** * Input : - SystemHandler: specifies the system handler pending bit to + 544:stm32lib/src/stm32f10x_nvic.c **** * check. + 545:stm32lib/src/stm32f10x_nvic.c **** * This parameter can be one of the following values: + 546:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_MemoryManage + 547:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_BusFault + 548:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_SVCall + 549:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 550:stm32lib/src/stm32f10x_nvic.c **** * Return : The new state of System Handler pending bit(SET or RESET). + 551:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 552:stm32lib/src/stm32f10x_nvic.c **** ITStatus NVIC_GetSystemHandlerPendingBitStatus(u32 SystemHandler) + 553:stm32lib/src/stm32f10x_nvic.c **** { + 841 .loc 1 553 0 + 842 @ args = 0, pretend = 0, frame = 0 + 843 @ frame_needed = 0, uses_anonymous_args = 0 + 844 @ link register save eliminated. + 845 .LVL48: + 554:stm32lib/src/stm32f10x_nvic.c **** ITStatus bitstatus = RESET; + 555:stm32lib/src/stm32f10x_nvic.c **** u32 tmp = 0x00, tmppos = 0x00; + 556:stm32lib/src/stm32f10x_nvic.c **** + 557:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 558:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_GET_PENDING_SYSTEM_HANDLER(SystemHandler)); + 559:stm32lib/src/stm32f10x_nvic.c **** + 560:stm32lib/src/stm32f10x_nvic.c **** tmppos = (SystemHandler >> 0x0A); + 561:stm32lib/src/stm32f10x_nvic.c **** tmppos &= (u32)0x0F; + 562:stm32lib/src/stm32f10x_nvic.c **** + 563:stm32lib/src/stm32f10x_nvic.c **** tmppos = (u32)0x01 << tmppos; + 846 .loc 1 563 0 + 847 027c C0F38320 ubfx r0, r0, #10, #4 + 848 .LVL49: + 849 0280 0123 movs r3, #1 + 850 0282 8340 lsls r3, r3, r0 + 851 .LVL50: + 564:stm32lib/src/stm32f10x_nvic.c **** + 565:stm32lib/src/stm32f10x_nvic.c **** tmp = SCB->SHCSR & tmppos; + 852 .loc 1 565 0 + 853 0284 044A ldr r2, .L94 + 854 0286 506A ldr r0, [r2, #36] + 855 0288 03EA0000 and r0, r3, r0 + 566:stm32lib/src/stm32f10x_nvic.c **** + 567:stm32lib/src/stm32f10x_nvic.c **** if (tmp == tmppos) + 568:stm32lib/src/stm32f10x_nvic.c **** { + 569:stm32lib/src/stm32f10x_nvic.c **** bitstatus = SET; + 570:stm32lib/src/stm32f10x_nvic.c **** } + 571:stm32lib/src/stm32f10x_nvic.c **** else + 572:stm32lib/src/stm32f10x_nvic.c **** { + 573:stm32lib/src/stm32f10x_nvic.c **** bitstatus = RESET; + 574:stm32lib/src/stm32f10x_nvic.c **** } + 575:stm32lib/src/stm32f10x_nvic.c **** return bitstatus; + 576:stm32lib/src/stm32f10x_nvic.c **** } + 856 .loc 1 576 0 + 857 028c 9842 cmp r0, r3 + 858 028e 14BF ite ne + 859 0290 0020 movne r0, #0 + 860 0292 0120 moveq r0, #1 + 861 0294 7047 bx lr + 862 .L95: + 863 0296 00BF .align 2 + 864 .L94: + 865 0298 00ED00E0 .word -536810240 + 866 .LFE47: + 868 .align 2 + 869 .global NVIC_SetSystemHandlerPendingBit + 870 .thumb + 871 .thumb_func + 873 NVIC_SetSystemHandlerPendingBit: + 874 .LFB48: + 577:stm32lib/src/stm32f10x_nvic.c **** + 578:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 579:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_SetSystemHandlerPendingBit + 580:stm32lib/src/stm32f10x_nvic.c **** * Description : Sets System Handler pending bit. + 581:stm32lib/src/stm32f10x_nvic.c **** * Input : - SystemHandler: specifies the system handler pending bit + 582:stm32lib/src/stm32f10x_nvic.c **** * to be set. + 583:stm32lib/src/stm32f10x_nvic.c **** * This parameter can be one of the following values: + 584:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_NMI + 585:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_PSV + 586:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_SysTick + 587:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 588:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 589:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 590:stm32lib/src/stm32f10x_nvic.c **** void NVIC_SetSystemHandlerPendingBit(u32 SystemHandler) + 591:stm32lib/src/stm32f10x_nvic.c **** { + 875 .loc 1 591 0 + 876 @ args = 0, pretend = 0, frame = 0 + 877 @ frame_needed = 0, uses_anonymous_args = 0 + 878 @ link register save eliminated. + 879 .LVL51: + 592:stm32lib/src/stm32f10x_nvic.c **** u32 tmp = 0x00; + 593:stm32lib/src/stm32f10x_nvic.c **** + 594:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 595:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_SET_PENDING_SYSTEM_HANDLER(SystemHandler)); + 596:stm32lib/src/stm32f10x_nvic.c **** + 597:stm32lib/src/stm32f10x_nvic.c **** /* Get the System Handler pending bit position */ + 598:stm32lib/src/stm32f10x_nvic.c **** tmp = SystemHandler & (u32)0x1F; + 599:stm32lib/src/stm32f10x_nvic.c **** /* Set the corresponding System Handler pending bit */ + 600:stm32lib/src/stm32f10x_nvic.c **** SCB->ICSR |= ((u32)0x01 << tmp); + 880 .loc 1 600 0 + 881 029c 00F01F00 and r0, r0, #31 + 882 .LVL52: + 883 02a0 0123 movs r3, #1 + 884 02a2 8340 lsls r3, r3, r0 + 885 02a4 024A ldr r2, .L98 + 886 02a6 5168 ldr r1, [r2, #4] + 887 02a8 0B43 orrs r3, r3, r1 + 888 02aa 5360 str r3, [r2, #4] + 601:stm32lib/src/stm32f10x_nvic.c **** } + 889 .loc 1 601 0 + 890 02ac 7047 bx lr + 891 .L99: + 892 02ae 00BF .align 2 + 893 .L98: + 894 02b0 00ED00E0 .word -536810240 + 895 .LFE48: + 897 .align 2 + 898 .global NVIC_ClearSystemHandlerPendingBit + 899 .thumb + 900 .thumb_func + 902 NVIC_ClearSystemHandlerPendingBit: + 903 .LFB49: + 602:stm32lib/src/stm32f10x_nvic.c **** + 603:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 604:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_ClearSystemHandlerPendingBit + 605:stm32lib/src/stm32f10x_nvic.c **** * Description : Clears System Handler pending bit. + 606:stm32lib/src/stm32f10x_nvic.c **** * Input : - SystemHandler: specifies the system handler pending bit to + 607:stm32lib/src/stm32f10x_nvic.c **** * be clear. + 608:stm32lib/src/stm32f10x_nvic.c **** * This parameter can be one of the following values: + 609:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_PSV + 610:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_SysTick + 611:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 612:stm32lib/src/stm32f10x_nvic.c **** * Return : None + 613:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 614:stm32lib/src/stm32f10x_nvic.c **** void NVIC_ClearSystemHandlerPendingBit(u32 SystemHandler) + 615:stm32lib/src/stm32f10x_nvic.c **** { + 904 .loc 1 615 0 + 905 @ args = 0, pretend = 0, frame = 0 + 906 @ frame_needed = 0, uses_anonymous_args = 0 + 907 @ link register save eliminated. + 908 .LVL53: + 616:stm32lib/src/stm32f10x_nvic.c **** u32 tmp = 0x00; + 617:stm32lib/src/stm32f10x_nvic.c **** + 618:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 619:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_CLEAR_SYSTEM_HANDLER(SystemHandler)); + 620:stm32lib/src/stm32f10x_nvic.c **** + 621:stm32lib/src/stm32f10x_nvic.c **** /* Get the System Handler pending bit position */ + 622:stm32lib/src/stm32f10x_nvic.c **** tmp = SystemHandler & (u32)0x1F; + 623:stm32lib/src/stm32f10x_nvic.c **** /* Clear the corresponding System Handler pending bit */ + 624:stm32lib/src/stm32f10x_nvic.c **** SCB->ICSR |= ((u32)0x01 << (tmp - 0x01)); + 909 .loc 1 624 0 + 910 02b4 00F01F00 and r0, r0, #31 + 911 .LVL54: + 912 02b8 0138 subs r0, r0, #1 + 913 02ba 0123 movs r3, #1 + 914 02bc 8340 lsls r3, r3, r0 + 915 02be 024A ldr r2, .L102 + 916 02c0 5168 ldr r1, [r2, #4] + 917 02c2 0B43 orrs r3, r3, r1 + 918 02c4 5360 str r3, [r2, #4] + 625:stm32lib/src/stm32f10x_nvic.c **** } + 919 .loc 1 625 0 + 920 02c6 7047 bx lr + 921 .L103: + 922 .align 2 + 923 .L102: + 924 02c8 00ED00E0 .word -536810240 + 925 .LFE49: + 927 .align 2 + 928 .global NVIC_GetSystemHandlerActiveBitStatus + 929 .thumb + 930 .thumb_func + 932 NVIC_GetSystemHandlerActiveBitStatus: + 933 .LFB50: + 626:stm32lib/src/stm32f10x_nvic.c **** + 627:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 628:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_GetSystemHandlerActiveBitStatus + 629:stm32lib/src/stm32f10x_nvic.c **** * Description : Checks whether the specified System handlers active bit is + 630:stm32lib/src/stm32f10x_nvic.c **** * set or not. + 631:stm32lib/src/stm32f10x_nvic.c **** * Input : - SystemHandler: specifies the system handler active bit to + 632:stm32lib/src/stm32f10x_nvic.c **** * check. + 633:stm32lib/src/stm32f10x_nvic.c **** * This parameter can be one of the following values: + 634:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_MemoryManage + 635:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_BusFault + 636:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_UsageFault + 637:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_SVCall + 638:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_DebugMonitor + 639:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_PSV + 640:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_SysTick + 641:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 642:stm32lib/src/stm32f10x_nvic.c **** * Return : The new state of System Handler active bit(SET or RESET). + 643:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 644:stm32lib/src/stm32f10x_nvic.c **** ITStatus NVIC_GetSystemHandlerActiveBitStatus(u32 SystemHandler) + 645:stm32lib/src/stm32f10x_nvic.c **** { + 934 .loc 1 645 0 + 935 @ args = 0, pretend = 0, frame = 0 + 936 @ frame_needed = 0, uses_anonymous_args = 0 + 937 @ link register save eliminated. + 938 .LVL55: + 646:stm32lib/src/stm32f10x_nvic.c **** ITStatus bitstatus = RESET; + 647:stm32lib/src/stm32f10x_nvic.c **** + 648:stm32lib/src/stm32f10x_nvic.c **** u32 tmp = 0x00, tmppos = 0x00; + 649:stm32lib/src/stm32f10x_nvic.c **** + 650:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 651:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_GET_ACTIVE_SYSTEM_HANDLER(SystemHandler)); + 652:stm32lib/src/stm32f10x_nvic.c **** + 653:stm32lib/src/stm32f10x_nvic.c **** tmppos = (SystemHandler >> 0x0E) & (u32)0x0F; + 654:stm32lib/src/stm32f10x_nvic.c **** + 655:stm32lib/src/stm32f10x_nvic.c **** tmppos = (u32)0x01 << tmppos; + 939 .loc 1 655 0 + 940 02cc C0F38330 ubfx r0, r0, #14, #4 + 941 .LVL56: + 942 02d0 0123 movs r3, #1 + 943 02d2 8340 lsls r3, r3, r0 + 944 .LVL57: + 656:stm32lib/src/stm32f10x_nvic.c **** + 657:stm32lib/src/stm32f10x_nvic.c **** tmp = SCB->SHCSR & tmppos; + 945 .loc 1 657 0 + 946 02d4 044A ldr r2, .L106 + 947 02d6 506A ldr r0, [r2, #36] + 948 02d8 03EA0000 and r0, r3, r0 + 658:stm32lib/src/stm32f10x_nvic.c **** + 659:stm32lib/src/stm32f10x_nvic.c **** if (tmp == tmppos) + 660:stm32lib/src/stm32f10x_nvic.c **** { + 661:stm32lib/src/stm32f10x_nvic.c **** bitstatus = SET; + 662:stm32lib/src/stm32f10x_nvic.c **** } + 663:stm32lib/src/stm32f10x_nvic.c **** else + 664:stm32lib/src/stm32f10x_nvic.c **** { + 665:stm32lib/src/stm32f10x_nvic.c **** bitstatus = RESET; + 666:stm32lib/src/stm32f10x_nvic.c **** } + 667:stm32lib/src/stm32f10x_nvic.c **** return bitstatus; + 668:stm32lib/src/stm32f10x_nvic.c **** } + 949 .loc 1 668 0 + 950 02dc 9842 cmp r0, r3 + 951 02de 14BF ite ne + 952 02e0 0020 movne r0, #0 + 953 02e2 0120 moveq r0, #1 + 954 02e4 7047 bx lr + 955 .L107: + 956 02e6 00BF .align 2 + 957 .L106: + 958 02e8 00ED00E0 .word -536810240 + 959 .LFE50: + 961 .align 2 + 962 .global NVIC_GetFaultHandlerSources + 963 .thumb + 964 .thumb_func + 966 NVIC_GetFaultHandlerSources: + 967 .LFB51: + 669:stm32lib/src/stm32f10x_nvic.c **** + 670:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 671:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_GetFaultHandlerSources + 672:stm32lib/src/stm32f10x_nvic.c **** * Description : Returns the system fault handlers sources. + 673:stm32lib/src/stm32f10x_nvic.c **** * Input : - SystemHandler: specifies the system handler to get its fault + 674:stm32lib/src/stm32f10x_nvic.c **** * sources. + 675:stm32lib/src/stm32f10x_nvic.c **** * This parameter can be one of the following values: + 676:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_HardFault + 677:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_MemoryManage + 678:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_BusFault + 679:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_UsageFault + 680:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_DebugMonitor + 681:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 682:stm32lib/src/stm32f10x_nvic.c **** * Return : Source of the fault handler. + 683:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 684:stm32lib/src/stm32f10x_nvic.c **** u32 NVIC_GetFaultHandlerSources(u32 SystemHandler) + 685:stm32lib/src/stm32f10x_nvic.c **** { + 968 .loc 1 685 0 + 969 @ args = 0, pretend = 0, frame = 0 + 970 @ frame_needed = 0, uses_anonymous_args = 0 + 971 @ link register save eliminated. + 972 .LVL58: + 686:stm32lib/src/stm32f10x_nvic.c **** u32 faultsources = 0x00; + 687:stm32lib/src/stm32f10x_nvic.c **** u32 tmpreg = 0x00, tmppos = 0x00; + 688:stm32lib/src/stm32f10x_nvic.c **** + 689:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 690:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_FAULT_SOURCE_SYSTEM_HANDLER(SystemHandler)); + 691:stm32lib/src/stm32f10x_nvic.c **** + 692:stm32lib/src/stm32f10x_nvic.c **** tmpreg = (SystemHandler >> 0x12) & (u32)0x03; + 973 .loc 1 692 0 + 974 02ec C0F38143 ubfx r3, r0, #18, #2 + 975 .LVL59: + 693:stm32lib/src/stm32f10x_nvic.c **** tmppos = (SystemHandler >> 0x14) & (u32)0x03; + 694:stm32lib/src/stm32f10x_nvic.c **** + 695:stm32lib/src/stm32f10x_nvic.c **** if (tmpreg == 0x00) + 976 .loc 1 695 0 + 977 02f0 13B9 cbnz r3, .L109 + 696:stm32lib/src/stm32f10x_nvic.c **** { + 697:stm32lib/src/stm32f10x_nvic.c **** faultsources = SCB->HFSR; + 978 .loc 1 697 0 + 979 02f2 0B4B ldr r3, .L114 + 980 .LVL60: + 981 02f4 D86A ldr r0, [r3, #44] + 982 .LVL61: + 983 02f6 11E0 b .L110 + 984 .LVL62: + 985 .L109: + 698:stm32lib/src/stm32f10x_nvic.c **** } + 699:stm32lib/src/stm32f10x_nvic.c **** else if (tmpreg == 0x01) + 986 .loc 1 699 0 + 987 02f8 012B cmp r3, #1 + 988 02fa 0DD1 bne .L111 + 700:stm32lib/src/stm32f10x_nvic.c **** { + 701:stm32lib/src/stm32f10x_nvic.c **** faultsources = SCB->CFSR >> (tmppos * 0x08); + 989 .loc 1 701 0 + 990 02fc 084B ldr r3, .L114 + 991 .LVL63: + 992 .loc 1 693 0 + 993 02fe C0F30151 ubfx r1, r0, #20, #2 + 994 .LVL64: + 995 .loc 1 701 0 + 996 0302 9A6A ldr r2, [r3, #40] + 997 0304 CB00 lsls r3, r1, #3 + 998 0306 32FA03F0 lsrs r0, r2, r3 + 999 .LVL65: + 702:stm32lib/src/stm32f10x_nvic.c **** if (tmppos != 0x02) + 1000 .loc 1 702 0 + 1001 030a 0229 cmp r1, #2 + 703:stm32lib/src/stm32f10x_nvic.c **** { + 704:stm32lib/src/stm32f10x_nvic.c **** faultsources &= (u32)0x0F; + 1002 .loc 1 704 0 + 1003 030c 14BF ite ne + 1004 030e 00F00F00 andne r0, r0, #15 + 1005 .LVL66: + 705:stm32lib/src/stm32f10x_nvic.c **** } + 706:stm32lib/src/stm32f10x_nvic.c **** else + 707:stm32lib/src/stm32f10x_nvic.c **** { + 708:stm32lib/src/stm32f10x_nvic.c **** faultsources &= (u32)0xFF; + 1006 .loc 1 708 0 + 1007 0312 00F0FF00 andeq r0, r0, #255 + 1008 0316 01E0 b .L110 + 1009 .LVL67: + 1010 .L111: + 709:stm32lib/src/stm32f10x_nvic.c **** } + 710:stm32lib/src/stm32f10x_nvic.c **** } + 711:stm32lib/src/stm32f10x_nvic.c **** else + 712:stm32lib/src/stm32f10x_nvic.c **** { + 713:stm32lib/src/stm32f10x_nvic.c **** faultsources = SCB->DFSR; + 1011 .loc 1 713 0 + 1012 0318 014B ldr r3, .L114 + 1013 .LVL68: + 1014 031a 186B ldr r0, [r3, #48] + 1015 .LVL69: + 1016 .L110: + 1017 .LVL70: + 714:stm32lib/src/stm32f10x_nvic.c **** } + 715:stm32lib/src/stm32f10x_nvic.c **** return faultsources; + 716:stm32lib/src/stm32f10x_nvic.c **** } + 1018 .loc 1 716 0 + 1019 031c 7047 bx lr + 1020 .L115: + 1021 031e 00BF .align 2 + 1022 .L114: + 1023 0320 00ED00E0 .word -536810240 + 1024 .LFE51: + 1026 .align 2 + 1027 .global NVIC_GetFaultAddress + 1028 .thumb + 1029 .thumb_func + 1031 NVIC_GetFaultAddress: + 1032 .LFB52: + 717:stm32lib/src/stm32f10x_nvic.c **** + 718:stm32lib/src/stm32f10x_nvic.c **** /******************************************************************************* + 719:stm32lib/src/stm32f10x_nvic.c **** * Function Name : NVIC_GetFaultAddress + 720:stm32lib/src/stm32f10x_nvic.c **** * Description : Returns the address of the location that generated a fault + 721:stm32lib/src/stm32f10x_nvic.c **** * handler. + 722:stm32lib/src/stm32f10x_nvic.c **** * Input : - SystemHandler: specifies the system handler to get its + 723:stm32lib/src/stm32f10x_nvic.c **** * fault address. + 724:stm32lib/src/stm32f10x_nvic.c **** * This parameter can be one of the following values: + 725:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_MemoryManage + 726:stm32lib/src/stm32f10x_nvic.c **** * - SystemHandler_BusFault + 727:stm32lib/src/stm32f10x_nvic.c **** * Output : None + 728:stm32lib/src/stm32f10x_nvic.c **** * Return : Fault address. + 729:stm32lib/src/stm32f10x_nvic.c **** *******************************************************************************/ + 730:stm32lib/src/stm32f10x_nvic.c **** u32 NVIC_GetFaultAddress(u32 SystemHandler) + 731:stm32lib/src/stm32f10x_nvic.c **** { + 1033 .loc 1 731 0 + 1034 @ args = 0, pretend = 0, frame = 0 + 1035 @ frame_needed = 0, uses_anonymous_args = 0 + 1036 @ link register save eliminated. + 1037 .LVL71: + 732:stm32lib/src/stm32f10x_nvic.c **** u32 faultaddress = 0x00; + 733:stm32lib/src/stm32f10x_nvic.c **** u32 tmp = 0x00; + 734:stm32lib/src/stm32f10x_nvic.c **** + 735:stm32lib/src/stm32f10x_nvic.c **** /* Check the parameters */ + 736:stm32lib/src/stm32f10x_nvic.c **** assert_param(IS_FAULT_ADDRESS_SYSTEM_HANDLER(SystemHandler)); + 737:stm32lib/src/stm32f10x_nvic.c **** + 738:stm32lib/src/stm32f10x_nvic.c **** tmp = (SystemHandler >> 0x16) & (u32)0x01; + 739:stm32lib/src/stm32f10x_nvic.c **** + 740:stm32lib/src/stm32f10x_nvic.c **** if (tmp == 0x00) + 1038 .loc 1 740 0 + 1039 0324 10F4800F tst r0, #4194304 + 741:stm32lib/src/stm32f10x_nvic.c **** { + 742:stm32lib/src/stm32f10x_nvic.c **** faultaddress = SCB->MMFAR; + 1040 .loc 1 742 0 + 1041 0328 0BBF itete eq + 1042 032a 024B ldreq r3, .L120 + 743:stm32lib/src/stm32f10x_nvic.c **** } + 744:stm32lib/src/stm32f10x_nvic.c **** else + 745:stm32lib/src/stm32f10x_nvic.c **** { + 746:stm32lib/src/stm32f10x_nvic.c **** faultaddress = SCB->BFAR; + 1043 .loc 1 746 0 + 1044 032c 014B ldrne r3, .L120 + 1045 .loc 1 742 0 + 1046 032e 586B ldreq r0, [r3, #52] + 1047 .LVL72: + 1048 .loc 1 746 0 + 1049 0330 986B ldrne r0, [r3, #56] + 1050 .LVL73: + 747:stm32lib/src/stm32f10x_nvic.c **** } + 748:stm32lib/src/stm32f10x_nvic.c **** return faultaddress; + 749:stm32lib/src/stm32f10x_nvic.c **** } + 1051 .loc 1 749 0 + 1052 0332 7047 bx lr + 1053 .L121: + 1054 .align 2 + 1055 .L120: + 1056 0334 00ED00E0 .word -536810240 + 1057 .LFE52: + 1335 .Letext0: +DEFINED SYMBOLS + *ABS*:00000000 stm32f10x_nvic.c + /tmp/ccCAjlzC.s:22 .text:00000000 $t + /tmp/ccCAjlzC.s:27 .text:00000000 NVIC_DeInit + /tmp/ccCAjlzC.s:69 .text:00000030 $d + /tmp/ccCAjlzC.s:72 .text:00000034 $t + /tmp/ccCAjlzC.s:77 .text:00000034 NVIC_SCBDeInit + /tmp/ccCAjlzC.s:117 .text:0000005c $d + /tmp/ccCAjlzC.s:121 .text:00000064 $t + /tmp/ccCAjlzC.s:126 .text:00000064 NVIC_PriorityGroupConfig + /tmp/ccCAjlzC.s:144 .text:00000074 $d + /tmp/ccCAjlzC.s:147 .text:00000078 $t + /tmp/ccCAjlzC.s:152 .text:00000078 NVIC_Init + /tmp/ccCAjlzC.s:244 .text:000000ec $d + /tmp/ccCAjlzC.s:248 .text:000000f4 $t + /tmp/ccCAjlzC.s:253 .text:000000f4 NVIC_StructInit + /tmp/ccCAjlzC.s:278 .text:00000100 NVIC_SETPRIMASK + /tmp/ccCAjlzC.s:304 .text:00000104 NVIC_RESETPRIMASK + /tmp/ccCAjlzC.s:329 .text:00000108 NVIC_SETFAULTMASK + /tmp/ccCAjlzC.s:354 .text:0000010c NVIC_RESETFAULTMASK + /tmp/ccCAjlzC.s:379 .text:00000110 NVIC_BASEPRICONFIG + /tmp/ccCAjlzC.s:407 .text:00000118 NVIC_GetBASEPRI + /tmp/ccCAjlzC.s:434 .text:00000120 NVIC_GetCurrentPendingIRQChannel + /tmp/ccCAjlzC.s:449 .text:0000012c $d + /tmp/ccCAjlzC.s:452 .text:00000130 $t + /tmp/ccCAjlzC.s:457 .text:00000130 NVIC_GetIRQChannelPendingBitStatus + /tmp/ccCAjlzC.s:485 .text:00000150 $d + /tmp/ccCAjlzC.s:488 .text:00000154 $t + /tmp/ccCAjlzC.s:493 .text:00000154 NVIC_SetIRQChannelPendingBit + /tmp/ccCAjlzC.s:508 .text:0000015c $d + /tmp/ccCAjlzC.s:511 .text:00000160 $t + /tmp/ccCAjlzC.s:516 .text:00000160 NVIC_ClearIRQChannelPendingBit + /tmp/ccCAjlzC.s:537 .text:00000174 $d + /tmp/ccCAjlzC.s:540 .text:00000178 $t + /tmp/ccCAjlzC.s:545 .text:00000178 NVIC_GetCurrentActiveHandler + /tmp/ccCAjlzC.s:561 .text:00000184 $d + /tmp/ccCAjlzC.s:564 .text:00000188 $t + /tmp/ccCAjlzC.s:569 .text:00000188 NVIC_GetIRQChannelActiveBitStatus + /tmp/ccCAjlzC.s:597 .text:000001a8 $d + /tmp/ccCAjlzC.s:600 .text:000001ac $t + /tmp/ccCAjlzC.s:605 .text:000001ac NVIC_GetCPUID + /tmp/ccCAjlzC.s:619 .text:000001b4 $d + /tmp/ccCAjlzC.s:622 .text:000001b8 $t + /tmp/ccCAjlzC.s:627 .text:000001b8 NVIC_SetVectorTable + /tmp/ccCAjlzC.s:646 .text:000001c8 $d + /tmp/ccCAjlzC.s:649 .text:000001cc $t + /tmp/ccCAjlzC.s:654 .text:000001cc NVIC_GenerateSystemReset + /tmp/ccCAjlzC.s:669 .text:000001d4 $d + /tmp/ccCAjlzC.s:673 .text:000001dc $t + /tmp/ccCAjlzC.s:678 .text:000001dc NVIC_GenerateCoreReset + /tmp/ccCAjlzC.s:693 .text:000001e4 $d + /tmp/ccCAjlzC.s:697 .text:000001ec $t + /tmp/ccCAjlzC.s:702 .text:000001ec NVIC_SystemLPConfig + /tmp/ccCAjlzC.s:728 .text:00000204 $d + /tmp/ccCAjlzC.s:731 .text:00000208 $t + /tmp/ccCAjlzC.s:736 .text:00000208 NVIC_SystemHandlerConfig + /tmp/ccCAjlzC.s:768 .text:0000022c $d + /tmp/ccCAjlzC.s:771 .text:00000230 $t + /tmp/ccCAjlzC.s:776 .text:00000230 NVIC_SystemHandlerPriorityConfig + /tmp/ccCAjlzC.s:831 .text:00000278 $d + /tmp/ccCAjlzC.s:834 .text:0000027c $t + /tmp/ccCAjlzC.s:839 .text:0000027c NVIC_GetSystemHandlerPendingBitStatus + /tmp/ccCAjlzC.s:865 .text:00000298 $d + /tmp/ccCAjlzC.s:868 .text:0000029c $t + /tmp/ccCAjlzC.s:873 .text:0000029c NVIC_SetSystemHandlerPendingBit + /tmp/ccCAjlzC.s:894 .text:000002b0 $d + /tmp/ccCAjlzC.s:897 .text:000002b4 $t + /tmp/ccCAjlzC.s:902 .text:000002b4 NVIC_ClearSystemHandlerPendingBit + /tmp/ccCAjlzC.s:924 .text:000002c8 $d + /tmp/ccCAjlzC.s:927 .text:000002cc $t + /tmp/ccCAjlzC.s:932 .text:000002cc NVIC_GetSystemHandlerActiveBitStatus + /tmp/ccCAjlzC.s:958 .text:000002e8 $d + /tmp/ccCAjlzC.s:961 .text:000002ec $t + /tmp/ccCAjlzC.s:966 .text:000002ec NVIC_GetFaultHandlerSources + /tmp/ccCAjlzC.s:1023 .text:00000320 $d + /tmp/ccCAjlzC.s:1026 .text:00000324 $t + /tmp/ccCAjlzC.s:1031 .text:00000324 NVIC_GetFaultAddress + /tmp/ccCAjlzC.s:1056 .text:00000334 $d + +NO UNDEFINED SYMBOLS diff --git a/src/stm32lib/src/stm32f10x_pwr.c b/src/stm32lib/src/stm32f10x_pwr.c new file mode 100644 index 0000000..e02594a --- /dev/null +++ b/src/stm32lib/src/stm32f10x_pwr.c @@ -0,0 +1,280 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_pwr.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the PWR firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_pwr.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* --------- PWR registers bit address in the alias region ---------- */
+#define PWR_OFFSET (PWR_BASE - PERIPH_BASE)
+
+/* --- CR Register ---*/
+/* Alias word address of DBP bit */
+#define CR_OFFSET (PWR_OFFSET + 0x00)
+#define DBP_BitNumber 0x08
+#define CR_DBP_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4))
+
+/* Alias word address of PVDE bit */
+#define PVDE_BitNumber 0x04
+#define CR_PVDE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4))
+
+/* --- CSR Register ---*/
+/* Alias word address of EWUP bit */
+#define CSR_OFFSET (PWR_OFFSET + 0x04)
+#define EWUP_BitNumber 0x08
+#define CSR_EWUP_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4))
+
+/* ------------------ PWR registers bit mask ------------------------ */
+/* CR register bit mask */
+#define CR_PDDS_Set ((u32)0x00000002)
+#define CR_DS_Mask ((u32)0xFFFFFFFC)
+#define CR_CWUF_Set ((u32)0x00000004)
+#define CR_PLS_Mask ((u32)0xFFFFFF1F)
+
+/* --------- Cortex System Control register bit mask ---------------- */
+/* Cortex System Control register address */
+#define SCB_SysCtrl ((u32)0xE000ED10)
+/* SLEEPDEEP bit mask */
+#define SysCtrl_SLEEPDEEP_Set ((u32)0x00000004)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : PWR_DeInit
+* Description : Deinitializes the PWR peripheral registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_DeInit(void)
+{
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, DISABLE);
+}
+
+/*******************************************************************************
+* Function Name : PWR_BackupAccessCmd
+* Description : Enables or disables access to the RTC and backup registers.
+* Input : - NewState: new state of the access to the RTC and backup
+* registers. This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_BackupAccessCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CR_DBP_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : PWR_PVDCmd
+* Description : Enables or disables the Power Voltage Detector(PVD).
+* Input : - NewState: new state of the PVD.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_PVDCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CR_PVDE_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : PWR_PVDLevelConfig
+* Description : Configures the voltage threshold detected by the Power Voltage
+* Detector(PVD).
+* Input : - PWR_PVDLevel: specifies the PVD detection level
+* This parameter can be one of the following values:
+* - PWR_PVDLevel_2V2: PVD detection level set to 2.2V
+* - PWR_PVDLevel_2V3: PVD detection level set to 2.3V
+* - PWR_PVDLevel_2V4: PVD detection level set to 2.4V
+* - PWR_PVDLevel_2V5: PVD detection level set to 2.5V
+* - PWR_PVDLevel_2V6: PVD detection level set to 2.6V
+* - PWR_PVDLevel_2V7: PVD detection level set to 2.7V
+* - PWR_PVDLevel_2V8: PVD detection level set to 2.8V
+* - PWR_PVDLevel_2V9: PVD detection level set to 2.9V
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_PVDLevelConfig(u32 PWR_PVDLevel)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel));
+
+ tmpreg = PWR->CR;
+
+ /* Clear PLS[7:5] bits */
+ tmpreg &= CR_PLS_Mask;
+
+ /* Set PLS[7:5] bits according to PWR_PVDLevel value */
+ tmpreg |= PWR_PVDLevel;
+
+ /* Store the new value */
+ PWR->CR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : PWR_WakeUpPinCmd
+* Description : Enables or disables the WakeUp Pin functionality.
+* Input : - NewState: new state of the WakeUp Pin functionality.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_WakeUpPinCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CSR_EWUP_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : PWR_EnterSTOPMode
+* Description : Enters STOP mode.
+* Input : - PWR_Regulator: specifies the regulator state in STOP mode.
+* This parameter can be one of the following values:
+* - PWR_Regulator_ON: STOP mode with regulator ON
+* - PWR_Regulator_LowPower: STOP mode with
+* regulator in low power mode
+* - PWR_STOPEntry: specifies if STOP mode in entered with WFI or
+* WFE instruction.
+* This parameter can be one of the following values:
+* - PWR_STOPEntry_WFI: enter STOP mode with WFI instruction
+* - PWR_STOPEntry_WFE: enter STOP mode with WFE instruction
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_EnterSTOPMode(u32 PWR_Regulator, u8 PWR_STOPEntry)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_PWR_REGULATOR(PWR_Regulator));
+ assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry));
+
+ /* Select the regulator state in STOP mode ---------------------------------*/
+ tmpreg = PWR->CR;
+
+ /* Clear PDDS and LPDS bits */
+ tmpreg &= CR_DS_Mask;
+
+ /* Set LPDS bit according to PWR_Regulator value */
+ tmpreg |= PWR_Regulator;
+
+ /* Store the new value */
+ PWR->CR = tmpreg;
+
+ /* Set SLEEPDEEP bit of Cortex System Control Register */
+ *(vu32 *) SCB_SysCtrl |= SysCtrl_SLEEPDEEP_Set;
+
+ /* Select STOP mode entry --------------------------------------------------*/
+ if(PWR_STOPEntry == PWR_STOPEntry_WFI)
+ {
+ /* Request Wait For Interrupt */
+ __WFI();
+ }
+ else
+ {
+ /* Request Wait For Event */
+ __WFE();
+ }
+}
+
+/*******************************************************************************
+* Function Name : PWR_EnterSTANDBYMode
+* Description : Enters STANDBY mode.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_EnterSTANDBYMode(void)
+{
+ /* Clear Wake-up flag */
+ PWR->CR |= CR_CWUF_Set;
+
+ /* Select STANDBY mode */
+ PWR->CR |= CR_PDDS_Set;
+
+ /* Set SLEEPDEEP bit of Cortex System Control Register */
+ *(vu32 *) SCB_SysCtrl |= SysCtrl_SLEEPDEEP_Set;
+
+ /* Request Wait For Interrupt */
+ __WFI();
+}
+
+/*******************************************************************************
+* Function Name : PWR_GetFlagStatus
+* Description : Checks whether the specified PWR flag is set or not.
+* Input : - PWR_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - PWR_FLAG_WU: Wake Up flag
+* - PWR_FLAG_SB: StandBy flag
+* - PWR_FLAG_PVDO: PVD Output
+* Output : None
+* Return : The new state of PWR_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus PWR_GetFlagStatus(u32 PWR_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_PWR_GET_FLAG(PWR_FLAG));
+
+ if ((PWR->CSR & PWR_FLAG) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+
+ /* Return the flag status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : PWR_ClearFlag
+* Description : Clears the PWR's pending flags.
+* Input : - PWR_FLAG: specifies the flag to clear.
+* This parameter can be one of the following values:
+* - PWR_FLAG_WU: Wake Up flag
+* - PWR_FLAG_SB: StandBy flag
+* Output : None
+* Return : None
+*******************************************************************************/
+void PWR_ClearFlag(u32 PWR_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG));
+
+ PWR->CR |= PWR_FLAG << 2;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_rcc.c b/src/stm32lib/src/stm32f10x_rcc.c new file mode 100644 index 0000000..0ab6387 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_rcc.c @@ -0,0 +1,1104 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_rcc.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the RCC firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ------------ RCC registers bit address in the alias region ----------- */
+#define RCC_OFFSET (RCC_BASE - PERIPH_BASE)
+
+/* --- CR Register ---*/
+/* Alias word address of HSION bit */
+#define CR_OFFSET (RCC_OFFSET + 0x00)
+#define HSION_BitNumber 0x00
+#define CR_HSION_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4))
+
+/* Alias word address of PLLON bit */
+#define PLLON_BitNumber 0x18
+#define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4))
+
+/* Alias word address of CSSON bit */
+#define CSSON_BitNumber 0x13
+#define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4))
+
+/* --- CFGR Register ---*/
+/* Alias word address of USBPRE bit */
+#define CFGR_OFFSET (RCC_OFFSET + 0x04)
+#define USBPRE_BitNumber 0x16
+#define CFGR_USBPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4))
+
+/* --- BDCR Register ---*/
+/* Alias word address of RTCEN bit */
+#define BDCR_OFFSET (RCC_OFFSET + 0x20)
+#define RTCEN_BitNumber 0x0F
+#define BDCR_RTCEN_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4))
+
+/* Alias word address of BDRST bit */
+#define BDRST_BitNumber 0x10
+#define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4))
+
+/* --- CSR Register ---*/
+/* Alias word address of LSION bit */
+#define CSR_OFFSET (RCC_OFFSET + 0x24)
+#define LSION_BitNumber 0x00
+#define CSR_LSION_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4))
+
+/* ---------------------- RCC registers bit mask ------------------------ */
+/* CR register bit mask */
+#define CR_HSEBYP_Reset ((u32)0xFFFBFFFF)
+#define CR_HSEBYP_Set ((u32)0x00040000)
+#define CR_HSEON_Reset ((u32)0xFFFEFFFF)
+#define CR_HSEON_Set ((u32)0x00010000)
+#define CR_HSITRIM_Mask ((u32)0xFFFFFF07)
+
+/* CFGR register bit mask */
+#define CFGR_PLL_Mask ((u32)0xFFC0FFFF)
+#define CFGR_PLLMull_Mask ((u32)0x003C0000)
+#define CFGR_PLLSRC_Mask ((u32)0x00010000)
+#define CFGR_PLLXTPRE_Mask ((u32)0x00020000)
+#define CFGR_SWS_Mask ((u32)0x0000000C)
+#define CFGR_SW_Mask ((u32)0xFFFFFFFC)
+#define CFGR_HPRE_Reset_Mask ((u32)0xFFFFFF0F)
+#define CFGR_HPRE_Set_Mask ((u32)0x000000F0)
+#define CFGR_PPRE1_Reset_Mask ((u32)0xFFFFF8FF)
+#define CFGR_PPRE1_Set_Mask ((u32)0x00000700)
+#define CFGR_PPRE2_Reset_Mask ((u32)0xFFFFC7FF)
+#define CFGR_PPRE2_Set_Mask ((u32)0x00003800)
+#define CFGR_ADCPRE_Reset_Mask ((u32)0xFFFF3FFF)
+#define CFGR_ADCPRE_Set_Mask ((u32)0x0000C000)
+
+/* CSR register bit mask */
+#define CSR_RMVF_Set ((u32)0x01000000)
+
+/* RCC Flag Mask */
+#define FLAG_Mask ((u8)0x1F)
+
+/* Typical Value of the HSI in Hz */
+#define HSI_Value ((u32)8000000)
+
+/* CIR register byte 2 (Bits[15:8]) base address */
+#define CIR_BYTE2_ADDRESS ((u32)0x40021009)
+/* CIR register byte 3 (Bits[23:16]) base address */
+#define CIR_BYTE3_ADDRESS ((u32)0x4002100A)
+
+/* CFGR register byte 4 (Bits[31:24]) base address */
+#define CFGR_BYTE4_ADDRESS ((u32)0x40021007)
+
+/* BDCR register base address */
+#define BDCR_ADDRESS (PERIPH_BASE + BDCR_OFFSET)
+
+/* Time out for HSE start up */
+#define HSEStartUp_TimeOut ((u16)0x01FF)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+static uc8 APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
+static uc8 ADCPrescTable[4] = {2, 4, 6, 8};
+
+static volatile FlagStatus HSEStatus;
+static vu32 StartUpCounter = 0;
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : RCC_DeInit
+* Description : Resets the RCC clock configuration to the default reset state.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_DeInit(void)
+{
+ /* Set HSION bit */
+ RCC->CR |= (u32)0x00000001;
+
+ /* Reset SW[1:0], HPRE[3:0], PPRE1[2:0], PPRE2[2:0], ADCPRE[1:0] and MCO[2:0] bits */
+ RCC->CFGR &= (u32)0xF8FF0000;
+
+ /* Reset HSEON, CSSON and PLLON bits */
+ RCC->CR &= (u32)0xFEF6FFFF;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= (u32)0xFFFBFFFF;
+
+ /* Reset PLLSRC, PLLXTPRE, PLLMUL[3:0] and USBPRE bits */
+ RCC->CFGR &= (u32)0xFF80FFFF;
+
+ /* Disable all interrupts */
+ RCC->CIR = 0x00000000;
+}
+
+/*******************************************************************************
+* Function Name : RCC_HSEConfig
+* Description : Configures the External High Speed oscillator (HSE).
+* HSE can not be stopped if it is used directly or through the
+* PLL as system clock.
+* Input : - RCC_HSE: specifies the new state of the HSE.
+* This parameter can be one of the following values:
+* - RCC_HSE_OFF: HSE oscillator OFF
+* - RCC_HSE_ON: HSE oscillator ON
+* - RCC_HSE_Bypass: HSE oscillator bypassed with external
+* clock
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_HSEConfig(u32 RCC_HSE)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_HSE(RCC_HSE));
+
+ /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/
+ /* Reset HSEON bit */
+ RCC->CR &= CR_HSEON_Reset;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= CR_HSEBYP_Reset;
+
+ /* Configure HSE (RCC_HSE_OFF is already covered by the code section above) */
+ switch(RCC_HSE)
+ {
+ case RCC_HSE_ON:
+ /* Set HSEON bit */
+ RCC->CR |= CR_HSEON_Set;
+ break;
+
+ case RCC_HSE_Bypass:
+ /* Set HSEBYP and HSEON bits */
+ RCC->CR |= CR_HSEBYP_Set | CR_HSEON_Set;
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_WaitForHSEStartUp
+* Description : Waits for HSE start-up.
+* Input : None
+* Output : None
+* Return : An ErrorStatus enumuration value:
+* - SUCCESS: HSE oscillator is stable and ready to use
+* - ERROR: HSE oscillator not yet ready
+*******************************************************************************/
+ErrorStatus RCC_WaitForHSEStartUp(void)
+{
+ ErrorStatus status = ERROR;
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY);
+ StartUpCounter++;
+ } while((HSEStatus == RESET) && (StartUpCounter != HSEStartUp_TimeOut));
+
+
+ if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET)
+ {
+ status = SUCCESS;
+ }
+ else
+ {
+ status = ERROR;
+ }
+
+ return (status);
+}
+
+/*******************************************************************************
+* Function Name : RCC_AdjustHSICalibrationValue
+* Description : Adjusts the Internal High Speed oscillator (HSI) calibration
+* value.
+* Input : - HSICalibrationValue: specifies the calibration trimming value.
+* This parameter must be a number between 0 and 0x1F.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_AdjustHSICalibrationValue(u8 HSICalibrationValue)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_CALIBRATION_VALUE(HSICalibrationValue));
+
+ tmpreg = RCC->CR;
+
+ /* Clear HSITRIM[4:0] bits */
+ tmpreg &= CR_HSITRIM_Mask;
+
+ /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */
+ tmpreg |= (u32)HSICalibrationValue << 3;
+
+ /* Store the new value */
+ RCC->CR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : RCC_HSICmd
+* Description : Enables or disables the Internal High Speed oscillator (HSI).
+* HSI can not be stopped if it is used directly or through the
+* PLL as system clock.
+* Input : - NewState: new state of the HSI.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_HSICmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CR_HSION_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : RCC_PLLConfig
+* Description : Configures the PLL clock source and multiplication factor.
+* This function must be used only when the PLL is disabled.
+* Input : - RCC_PLLSource: specifies the PLL entry clock source.
+* This parameter can be one of the following values:
+* - RCC_PLLSource_HSI_Div2: HSI oscillator clock divided
+* by 2 selected as PLL clock entry
+* - RCC_PLLSource_HSE_Div1: HSE oscillator clock selected
+* as PLL clock entry
+* - RCC_PLLSource_HSE_Div2: HSE oscillator clock divided
+* by 2 selected as PLL clock entry
+* - RCC_PLLMul: specifies the PLL multiplication factor.
+* This parameter can be RCC_PLLMul_x where x:[2,16]
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_PLLConfig(u32 RCC_PLLSource, u32 RCC_PLLMul)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource));
+ assert_param(IS_RCC_PLL_MUL(RCC_PLLMul));
+
+ tmpreg = RCC->CFGR;
+
+ /* Clear PLLSRC, PLLXTPRE and PLLMUL[3:0] bits */
+ tmpreg &= CFGR_PLL_Mask;
+
+ /* Set the PLL configuration bits */
+ tmpreg |= RCC_PLLSource | RCC_PLLMul;
+
+ /* Store the new value */
+ RCC->CFGR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : RCC_PLLCmd
+* Description : Enables or disables the PLL.
+* The PLL can not be disabled if it is used as system clock.
+* Input : - NewState: new state of the PLL.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_PLLCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CR_PLLON_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : RCC_SYSCLKConfig
+* Description : Configures the system clock (SYSCLK).
+* Input : - RCC_SYSCLKSource: specifies the clock source used as system
+* clock. This parameter can be one of the following values:
+* - RCC_SYSCLKSource_HSI: HSI selected as system clock
+* - RCC_SYSCLKSource_HSE: HSE selected as system clock
+* - RCC_SYSCLKSource_PLLCLK: PLL selected as system clock
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_SYSCLKConfig(u32 RCC_SYSCLKSource)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource));
+
+ tmpreg = RCC->CFGR;
+
+ /* Clear SW[1:0] bits */
+ tmpreg &= CFGR_SW_Mask;
+
+ /* Set SW[1:0] bits according to RCC_SYSCLKSource value */
+ tmpreg |= RCC_SYSCLKSource;
+
+ /* Store the new value */
+ RCC->CFGR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : RCC_GetSYSCLKSource
+* Description : Returns the clock source used as system clock.
+* Input : None
+* Output : None
+* Return : The clock source used as system clock. The returned value can
+* be one of the following:
+* - 0x00: HSI used as system clock
+* - 0x04: HSE used as system clock
+* - 0x08: PLL used as system clock
+*******************************************************************************/
+u8 RCC_GetSYSCLKSource(void)
+{
+ return ((u8)(RCC->CFGR & CFGR_SWS_Mask));
+}
+
+/*******************************************************************************
+* Function Name : RCC_HCLKConfig
+* Description : Configures the AHB clock (HCLK).
+* Input : - RCC_SYSCLK: defines the AHB clock divider. This clock is
+* derived from the system clock (SYSCLK).
+* This parameter can be one of the following values:
+* - RCC_SYSCLK_Div1: AHB clock = SYSCLK
+* - RCC_SYSCLK_Div2: AHB clock = SYSCLK/2
+* - RCC_SYSCLK_Div4: AHB clock = SYSCLK/4
+* - RCC_SYSCLK_Div8: AHB clock = SYSCLK/8
+* - RCC_SYSCLK_Div16: AHB clock = SYSCLK/16
+* - RCC_SYSCLK_Div64: AHB clock = SYSCLK/64
+* - RCC_SYSCLK_Div128: AHB clock = SYSCLK/128
+* - RCC_SYSCLK_Div256: AHB clock = SYSCLK/256
+* - RCC_SYSCLK_Div512: AHB clock = SYSCLK/512
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_HCLKConfig(u32 RCC_SYSCLK)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_HCLK(RCC_SYSCLK));
+
+ tmpreg = RCC->CFGR;
+
+ /* Clear HPRE[3:0] bits */
+ tmpreg &= CFGR_HPRE_Reset_Mask;
+
+ /* Set HPRE[3:0] bits according to RCC_SYSCLK value */
+ tmpreg |= RCC_SYSCLK;
+
+ /* Store the new value */
+ RCC->CFGR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : RCC_PCLK1Config
+* Description : Configures the Low Speed APB clock (PCLK1).
+* Input : - RCC_HCLK: defines the APB1 clock divider. This clock is
+* derived from the AHB clock (HCLK).
+* This parameter can be one of the following values:
+* - RCC_HCLK_Div1: APB1 clock = HCLK
+* - RCC_HCLK_Div2: APB1 clock = HCLK/2
+* - RCC_HCLK_Div4: APB1 clock = HCLK/4
+* - RCC_HCLK_Div8: APB1 clock = HCLK/8
+* - RCC_HCLK_Div16: APB1 clock = HCLK/16
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_PCLK1Config(u32 RCC_HCLK)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_PCLK(RCC_HCLK));
+
+ tmpreg = RCC->CFGR;
+
+ /* Clear PPRE1[2:0] bits */
+ tmpreg &= CFGR_PPRE1_Reset_Mask;
+
+ /* Set PPRE1[2:0] bits according to RCC_HCLK value */
+ tmpreg |= RCC_HCLK;
+
+ /* Store the new value */
+ RCC->CFGR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : RCC_PCLK2Config
+* Description : Configures the High Speed APB clock (PCLK2).
+* Input : - RCC_HCLK: defines the APB2 clock divider. This clock is
+* derived from the AHB clock (HCLK).
+* This parameter can be one of the following values:
+* - RCC_HCLK_Div1: APB2 clock = HCLK
+* - RCC_HCLK_Div2: APB2 clock = HCLK/2
+* - RCC_HCLK_Div4: APB2 clock = HCLK/4
+* - RCC_HCLK_Div8: APB2 clock = HCLK/8
+* - RCC_HCLK_Div16: APB2 clock = HCLK/16
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_PCLK2Config(u32 RCC_HCLK)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_PCLK(RCC_HCLK));
+
+ tmpreg = RCC->CFGR;
+
+ /* Clear PPRE2[2:0] bits */
+ tmpreg &= CFGR_PPRE2_Reset_Mask;
+
+ /* Set PPRE2[2:0] bits according to RCC_HCLK value */
+ tmpreg |= RCC_HCLK << 3;
+
+ /* Store the new value */
+ RCC->CFGR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : RCC_ITConfig
+* Description : Enables or disables the specified RCC interrupts.
+* Input : - RCC_IT: specifies the RCC interrupt sources to be enabled
+* or disabled.
+* This parameter can be any combination of the following values:
+* - RCC_IT_LSIRDY: LSI ready interrupt
+* - RCC_IT_LSERDY: LSE ready interrupt
+* - RCC_IT_HSIRDY: HSI ready interrupt
+* - RCC_IT_HSERDY: HSE ready interrupt
+* - RCC_IT_PLLRDY: PLL ready interrupt
+* - NewState: new state of the specified RCC interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_ITConfig(u8 RCC_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_IT(RCC_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Perform Byte access to RCC_CIR[12:8] bits to enable the selected interrupts */
+ *(vu8 *) CIR_BYTE2_ADDRESS |= RCC_IT;
+ }
+ else
+ {
+ /* Perform Byte access to RCC_CIR[12:8] bits to disable the selected interrupts */
+ *(vu8 *) CIR_BYTE2_ADDRESS &= (u8)~RCC_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_USBCLKConfig
+* Description : Configures the USB clock (USBCLK).
+* Input : - RCC_USBCLKSource: specifies the USB clock source. This clock
+* is derived from the PLL output.
+* This parameter can be one of the following values:
+* - RCC_USBCLKSource_PLLCLK_1Div5: PLL clock divided by 1,5
+* selected as USB clock source
+* - RCC_USBCLKSource_PLLCLK_Div1: PLL clock selected as USB
+* clock source
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_USBCLKConfig(u32 RCC_USBCLKSource)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_USBCLK_SOURCE(RCC_USBCLKSource));
+
+ *(vu32 *) CFGR_USBPRE_BB = RCC_USBCLKSource;
+}
+
+/*******************************************************************************
+* Function Name : RCC_ADCCLKConfig
+* Description : Configures the ADC clock (ADCCLK).
+* Input : - RCC_PCLK2: defines the ADC clock divider. This clock is
+* derived from the APB2 clock (PCLK2).
+* This parameter can be one of the following values:
+* - RCC_PCLK2_Div2: ADC clock = PCLK2/2
+* - RCC_PCLK2_Div4: ADC clock = PCLK2/4
+* - RCC_PCLK2_Div6: ADC clock = PCLK2/6
+* - RCC_PCLK2_Div8: ADC clock = PCLK2/8
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_ADCCLKConfig(u32 RCC_PCLK2)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_ADCCLK(RCC_PCLK2));
+
+ tmpreg = RCC->CFGR;
+
+ /* Clear ADCPRE[1:0] bits */
+ tmpreg &= CFGR_ADCPRE_Reset_Mask;
+
+ /* Set ADCPRE[1:0] bits according to RCC_PCLK2 value */
+ tmpreg |= RCC_PCLK2;
+
+ /* Store the new value */
+ RCC->CFGR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : RCC_LSEConfig
+* Description : Configures the External Low Speed oscillator (LSE).
+* Input : - RCC_LSE: specifies the new state of the LSE.
+* This parameter can be one of the following values:
+* - RCC_LSE_OFF: LSE oscillator OFF
+* - RCC_LSE_ON: LSE oscillator ON
+* - RCC_LSE_Bypass: LSE oscillator bypassed with external
+* clock
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_LSEConfig(u8 RCC_LSE)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_LSE(RCC_LSE));
+
+ /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/
+ /* Reset LSEON bit */
+ *(vu8 *) BDCR_ADDRESS = RCC_LSE_OFF;
+
+ /* Reset LSEBYP bit */
+ *(vu8 *) BDCR_ADDRESS = RCC_LSE_OFF;
+
+ /* Configure LSE (RCC_LSE_OFF is already covered by the code section above) */
+ switch(RCC_LSE)
+ {
+ case RCC_LSE_ON:
+ /* Set LSEON bit */
+ *(vu8 *) BDCR_ADDRESS = RCC_LSE_ON;
+ break;
+
+ case RCC_LSE_Bypass:
+ /* Set LSEBYP and LSEON bits */
+ *(vu8 *) BDCR_ADDRESS = RCC_LSE_Bypass | RCC_LSE_ON;
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_LSICmd
+* Description : Enables or disables the Internal Low Speed oscillator (LSI).
+* LSI can not be disabled if the IWDG is running.
+* Input : - NewState: new state of the LSI.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_LSICmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CSR_LSION_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : RCC_RTCCLKConfig
+* Description : Configures the RTC clock (RTCCLK).
+* Once the RTC clock is selected it can’t be changed unless the
+* Backup domain is reset.
+* Input : - RCC_RTCCLKSource: specifies the RTC clock source.
+* This parameter can be one of the following values:
+* - RCC_RTCCLKSource_LSE: LSE selected as RTC clock
+* - RCC_RTCCLKSource_LSI: LSI selected as RTC clock
+* - RCC_RTCCLKSource_HSE_Div128: HSE clock divided by 128
+* selected as RTC clock
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_RTCCLKConfig(u32 RCC_RTCCLKSource)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource));
+
+ /* Select the RTC clock source */
+ RCC->BDCR |= RCC_RTCCLKSource;
+}
+
+/*******************************************************************************
+* Function Name : RCC_RTCCLKCmd
+* Description : Enables or disables the RTC clock.
+* This function must be used only after the RTC clock was
+* selected using the RCC_RTCCLKConfig function.
+* Input : - NewState: new state of the RTC clock.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_RTCCLKCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) BDCR_RTCEN_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : RCC_GetClocksFreq
+* Description : Returns the frequencies of different on chip clocks.
+* Input : - RCC_Clocks: pointer to a RCC_ClocksTypeDef structure which
+* will hold the clocks frequencies.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)
+{
+ u32 tmp = 0, pllmull = 0, pllsource = 0, presc = 0;
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+ tmp = RCC->CFGR & CFGR_SWS_Mask;
+
+ switch (tmp)
+ {
+ case 0x00: /* HSI used as system clock */
+ RCC_Clocks->SYSCLK_Frequency = HSI_Value;
+ break;
+
+ case 0x04: /* HSE used as system clock */
+ RCC_Clocks->SYSCLK_Frequency = HSE_Value;
+ break;
+
+ case 0x08: /* PLL used as system clock */
+ /* Get PLL clock source and multiplication factor ----------------------*/
+ pllmull = RCC->CFGR & CFGR_PLLMull_Mask;
+ pllmull = ( pllmull >> 18) + 2;
+
+ pllsource = RCC->CFGR & CFGR_PLLSRC_Mask;
+
+ if (pllsource == 0x00)
+ {/* HSI oscillator clock divided by 2 selected as PLL clock entry */
+ RCC_Clocks->SYSCLK_Frequency = (HSI_Value >> 1) * pllmull;
+ }
+ else
+ {/* HSE selected as PLL clock entry */
+
+ if ((RCC->CFGR & CFGR_PLLXTPRE_Mask) != (u32)RESET)
+ {/* HSE oscillator clock divided by 2 */
+
+ RCC_Clocks->SYSCLK_Frequency = (HSE_Value >> 1) * pllmull;
+ }
+ else
+ {
+ RCC_Clocks->SYSCLK_Frequency = HSE_Value * pllmull;
+ }
+ }
+ break;
+
+ default:
+ RCC_Clocks->SYSCLK_Frequency = HSI_Value;
+ break;
+ }
+
+ /* Compute HCLK, PCLK1, PCLK2 and ADCCLK clocks frequencies ----------------*/
+ /* Get HCLK prescaler */
+ tmp = RCC->CFGR & CFGR_HPRE_Set_Mask;
+ tmp = tmp >> 4;
+ presc = APBAHBPrescTable[tmp];
+
+ /* HCLK clock frequency */
+ RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> presc;
+
+ /* Get PCLK1 prescaler */
+ tmp = RCC->CFGR & CFGR_PPRE1_Set_Mask;
+ tmp = tmp >> 8;
+ presc = APBAHBPrescTable[tmp];
+
+ /* PCLK1 clock frequency */
+ RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc;
+
+ /* Get PCLK2 prescaler */
+ tmp = RCC->CFGR & CFGR_PPRE2_Set_Mask;
+ tmp = tmp >> 11;
+ presc = APBAHBPrescTable[tmp];
+
+ /* PCLK2 clock frequency */
+ RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> presc;
+
+ /* Get ADCCLK prescaler */
+ tmp = RCC->CFGR & CFGR_ADCPRE_Set_Mask;
+ tmp = tmp >> 14;
+ presc = ADCPrescTable[tmp];
+
+ /* ADCCLK clock frequency */
+ RCC_Clocks->ADCCLK_Frequency = RCC_Clocks->PCLK2_Frequency / presc;
+}
+
+/*******************************************************************************
+* Function Name : RCC_AHBPeriphClockCmd
+* Description : Enables or disables the AHB peripheral clock.
+* Input : - RCC_AHBPeriph: specifies the AHB peripheral to gates its clock.
+* This parameter can be any combination of the following values:
+* - RCC_AHBPeriph_DMA1
+* - RCC_AHBPeriph_DMA2
+* - RCC_AHBPeriph_SRAM
+* - RCC_AHBPeriph_FLITF
+* - RCC_AHBPeriph_CRC
+* - RCC_AHBPeriph_FSMC
+* - RCC_AHBPeriph_SDIO
+* SRAM and FLITF clock can be disabled only during sleep mode.
+* - NewState: new state of the specified peripheral clock.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_AHBPeriphClockCmd(u32 RCC_AHBPeriph, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_AHB_PERIPH(RCC_AHBPeriph));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ RCC->AHBENR |= RCC_AHBPeriph;
+ }
+ else
+ {
+ RCC->AHBENR &= ~RCC_AHBPeriph;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_APB2PeriphClockCmd
+* Description : Enables or disables the High Speed APB (APB2) peripheral clock.
+* Input : - RCC_APB2Periph: specifies the APB2 peripheral to gates its
+* clock.
+* This parameter can be any combination of the following values:
+* - RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB,
+* RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE,
+* RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1,
+* RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1,
+* RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3,
+* RCC_APB2Periph_ALL
+* - NewState: new state of the specified peripheral clock.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_APB2PeriphClockCmd(u32 RCC_APB2Periph, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ RCC->APB2ENR |= RCC_APB2Periph;
+ }
+ else
+ {
+ RCC->APB2ENR &= ~RCC_APB2Periph;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_APB1PeriphClockCmd
+* Description : Enables or disables the Low Speed APB (APB1) peripheral clock.
+* Input : - RCC_APB1Periph: specifies the APB1 peripheral to gates its
+* clock.
+* This parameter can be any combination of the following values:
+* - RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4,
+* RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7,
+* RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3,
+* RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4,
+* RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2,
+* RCC_APB1Periph_USB, RCC_APB1Periph_CAN, RCC_APB1Periph_BKP,
+* RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_ALL
+* - NewState: new state of the specified peripheral clock.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_APB1PeriphClockCmd(u32 RCC_APB1Periph, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ RCC->APB1ENR |= RCC_APB1Periph;
+ }
+ else
+ {
+ RCC->APB1ENR &= ~RCC_APB1Periph;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_APB2PeriphResetCmd
+* Description : Forces or releases High Speed APB (APB2) peripheral reset.
+* Input : - RCC_APB2Periph: specifies the APB2 peripheral to reset.
+* This parameter can be any combination of the following values:
+* - RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB,
+* RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE,
+* RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1,
+* RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1,
+* RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3,
+* RCC_APB2Periph_ALL
+* - NewState: new state of the specified peripheral reset.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_APB2PeriphResetCmd(u32 RCC_APB2Periph, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ RCC->APB2RSTR |= RCC_APB2Periph;
+ }
+ else
+ {
+ RCC->APB2RSTR &= ~RCC_APB2Periph;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_APB1PeriphResetCmd
+* Description : Forces or releases Low Speed APB (APB1) peripheral reset.
+* Input : - RCC_APB1Periph: specifies the APB1 peripheral to reset.
+* This parameter can be any combination of the following values:
+* - RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4,
+* RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7,
+* RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3,
+* RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4,
+* RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2,
+* RCC_APB1Periph_USB, RCC_APB1Periph_CAN, RCC_APB1Periph_BKP,
+* RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_ALL
+* - NewState: new state of the specified peripheral clock.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_APB1PeriphResetCmd(u32 RCC_APB1Periph, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ RCC->APB1RSTR |= RCC_APB1Periph;
+ }
+ else
+ {
+ RCC->APB1RSTR &= ~RCC_APB1Periph;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RCC_BackupResetCmd
+* Description : Forces or releases the Backup domain reset.
+* Input : - NewState: new state of the Backup domain reset.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_BackupResetCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) BDCR_BDRST_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : RCC_ClockSecuritySystemCmd
+* Description : Enables or disables the Clock Security System.
+* Input : - NewState: new state of the Clock Security System..
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_ClockSecuritySystemCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CR_CSSON_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : RCC_MCOConfig
+* Description : Selects the clock source to output on MCO pin.
+* Input : - RCC_MCO: specifies the clock source to output.
+* This parameter can be one of the following values:
+* - RCC_MCO_NoClock: No clock selected
+* - RCC_MCO_SYSCLK: System clock selected
+* - RCC_MCO_HSI: HSI oscillator clock selected
+* - RCC_MCO_HSE: HSE oscillator clock selected
+* - RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_MCOConfig(u8 RCC_MCO)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_MCO(RCC_MCO));
+
+ /* Perform Byte access to MCO[2:0] bits to select the MCO source */
+ *(vu8 *) CFGR_BYTE4_ADDRESS = RCC_MCO;
+}
+
+/*******************************************************************************
+* Function Name : RCC_GetFlagStatus
+* Description : Checks whether the specified RCC flag is set or not.
+* Input : - RCC_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - RCC_FLAG_HSIRDY: HSI oscillator clock ready
+* - RCC_FLAG_HSERDY: HSE oscillator clock ready
+* - RCC_FLAG_PLLRDY: PLL clock ready
+* - RCC_FLAG_LSERDY: LSE oscillator clock ready
+* - RCC_FLAG_LSIRDY: LSI oscillator clock ready
+* - RCC_FLAG_PINRST: Pin reset
+* - RCC_FLAG_PORRST: POR/PDR reset
+* - RCC_FLAG_SFTRST: Software reset
+* - RCC_FLAG_IWDGRST: Independent Watchdog reset
+* - RCC_FLAG_WWDGRST: Window Watchdog reset
+* - RCC_FLAG_LPWRRST: Low Power reset
+* Output : None
+* Return : The new state of RCC_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus RCC_GetFlagStatus(u8 RCC_FLAG)
+{
+ u32 tmp = 0;
+ u32 statusreg = 0;
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_FLAG(RCC_FLAG));
+
+ /* Get the RCC register index */
+ tmp = RCC_FLAG >> 5;
+
+ if (tmp == 1) /* The flag to check is in CR register */
+ {
+ statusreg = RCC->CR;
+ }
+ else if (tmp == 2) /* The flag to check is in BDCR register */
+ {
+ statusreg = RCC->BDCR;
+ }
+ else /* The flag to check is in CSR register */
+ {
+ statusreg = RCC->CSR;
+ }
+
+ /* Get the flag position */
+ tmp = RCC_FLAG & FLAG_Mask;
+
+ if ((statusreg & ((u32)1 << tmp)) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+
+ /* Return the flag status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : RCC_ClearFlag
+* Description : Clears the RCC reset flags.
+* The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST,
+* RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST,
+* RCC_FLAG_LPWRRST
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_ClearFlag(void)
+{
+ /* Set RMVF bit to clear the reset flags */
+ RCC->CSR |= CSR_RMVF_Set;
+}
+
+/*******************************************************************************
+* Function Name : RCC_GetITStatus
+* Description : Checks whether the specified RCC interrupt has occurred or not.
+* Input : - RCC_IT: specifies the RCC interrupt source to check.
+* This parameter can be one of the following values:
+* - RCC_IT_LSIRDY: LSI ready interrupt
+* - RCC_IT_LSERDY: LSE ready interrupt
+* - RCC_IT_HSIRDY: HSI ready interrupt
+* - RCC_IT_HSERDY: HSE ready interrupt
+* - RCC_IT_PLLRDY: PLL ready interrupt
+* - RCC_IT_CSS: Clock Security System interrupt
+* Output : None
+* Return : The new state of RCC_IT (SET or RESET).
+*******************************************************************************/
+ITStatus RCC_GetITStatus(u8 RCC_IT)
+{
+ ITStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_RCC_GET_IT(RCC_IT));
+
+ /* Check the status of the specified RCC interrupt */
+ if ((RCC->CIR & RCC_IT) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+
+ /* Return the RCC_IT status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : RCC_ClearITPendingBit
+* Description : Clears the RCC’s interrupt pending bits.
+* Input : - RCC_IT: specifies the interrupt pending bit to clear.
+* This parameter can be any combination of the following values:
+* - RCC_IT_LSIRDY: LSI ready interrupt
+* - RCC_IT_LSERDY: LSE ready interrupt
+* - RCC_IT_HSIRDY: HSI ready interrupt
+* - RCC_IT_HSERDY: HSE ready interrupt
+* - RCC_IT_PLLRDY: PLL ready interrupt
+* - RCC_IT_CSS: Clock Security System interrupt
+* Output : None
+* Return : None
+*******************************************************************************/
+void RCC_ClearITPendingBit(u8 RCC_IT)
+{
+ /* Check the parameters */
+ assert_param(IS_RCC_CLEAR_IT(RCC_IT));
+
+ /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt
+ pending bits */
+ *(vu8 *) CIR_BYTE3_ADDRESS = RCC_IT;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_rcc.lst b/src/stm32lib/src/stm32f10x_rcc.lst new file mode 100644 index 0000000..6bf9d44 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_rcc.lst @@ -0,0 +1,2271 @@ + 1 .syntax unified + 2 .cpu cortex-m3 + 3 .fpu softvfp + 4 .eabi_attribute 20, 1 + 5 .eabi_attribute 21, 1 + 6 .eabi_attribute 23, 3 + 7 .eabi_attribute 24, 1 + 8 .eabi_attribute 25, 1 + 9 .eabi_attribute 26, 1 + 10 .eabi_attribute 30, 4 + 11 .eabi_attribute 18, 4 + 12 .thumb + 13 .file "stm32f10x_rcc.c" + 21 .Ltext0: + 22 .align 2 + 23 .global RCC_DeInit + 24 .thumb + 25 .thumb_func + 27 RCC_DeInit: + 28 .LFB23: + 29 .file 1 "stm32lib/src/stm32f10x_rcc.c" + 1:stm32lib/src/stm32f10x_rcc.c **** /******************** (C) COPYRIGHT 2008 STMicroelectronics ******************** + 2:stm32lib/src/stm32f10x_rcc.c **** * File Name : stm32f10x_rcc.c + 3:stm32lib/src/stm32f10x_rcc.c **** * Author : MCD Application Team + 4:stm32lib/src/stm32f10x_rcc.c **** * Version : V2.0.2 + 5:stm32lib/src/stm32f10x_rcc.c **** * Date : 07/11/2008 + 6:stm32lib/src/stm32f10x_rcc.c **** * Description : This file provides all the RCC firmware functions. + 7:stm32lib/src/stm32f10x_rcc.c **** ******************************************************************************** + 8:stm32lib/src/stm32f10x_rcc.c **** * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + 9:stm32lib/src/stm32f10x_rcc.c **** * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. + 10:stm32lib/src/stm32f10x_rcc.c **** * AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, + 11:stm32lib/src/stm32f10x_rcc.c **** * INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE + 12:stm32lib/src/stm32f10x_rcc.c **** * CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING + 13:stm32lib/src/stm32f10x_rcc.c **** * INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + 14:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 15:stm32lib/src/stm32f10x_rcc.c **** + 16:stm32lib/src/stm32f10x_rcc.c **** /* Includes ------------------------------------------------------------------*/ + 17:stm32lib/src/stm32f10x_rcc.c **** #include "stm32f10x_rcc.h" + 18:stm32lib/src/stm32f10x_rcc.c **** + 19:stm32lib/src/stm32f10x_rcc.c **** /* Private typedef -----------------------------------------------------------*/ + 20:stm32lib/src/stm32f10x_rcc.c **** /* Private define ------------------------------------------------------------*/ + 21:stm32lib/src/stm32f10x_rcc.c **** /* ------------ RCC registers bit address in the alias region ----------- */ + 22:stm32lib/src/stm32f10x_rcc.c **** #define RCC_OFFSET (RCC_BASE - PERIPH_BASE) + 23:stm32lib/src/stm32f10x_rcc.c **** + 24:stm32lib/src/stm32f10x_rcc.c **** /* --- CR Register ---*/ + 25:stm32lib/src/stm32f10x_rcc.c **** /* Alias word address of HSION bit */ + 26:stm32lib/src/stm32f10x_rcc.c **** #define CR_OFFSET (RCC_OFFSET + 0x00) + 27:stm32lib/src/stm32f10x_rcc.c **** #define HSION_BitNumber 0x00 + 28:stm32lib/src/stm32f10x_rcc.c **** #define CR_HSION_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4)) + 29:stm32lib/src/stm32f10x_rcc.c **** + 30:stm32lib/src/stm32f10x_rcc.c **** /* Alias word address of PLLON bit */ + 31:stm32lib/src/stm32f10x_rcc.c **** #define PLLON_BitNumber 0x18 + 32:stm32lib/src/stm32f10x_rcc.c **** #define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4)) + 33:stm32lib/src/stm32f10x_rcc.c **** + 34:stm32lib/src/stm32f10x_rcc.c **** /* Alias word address of CSSON bit */ + 35:stm32lib/src/stm32f10x_rcc.c **** #define CSSON_BitNumber 0x13 + 36:stm32lib/src/stm32f10x_rcc.c **** #define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4)) + 37:stm32lib/src/stm32f10x_rcc.c **** + 38:stm32lib/src/stm32f10x_rcc.c **** /* --- CFGR Register ---*/ + 39:stm32lib/src/stm32f10x_rcc.c **** /* Alias word address of USBPRE bit */ + 40:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_OFFSET (RCC_OFFSET + 0x04) + 41:stm32lib/src/stm32f10x_rcc.c **** #define USBPRE_BitNumber 0x16 + 42:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_USBPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4)) + 43:stm32lib/src/stm32f10x_rcc.c **** + 44:stm32lib/src/stm32f10x_rcc.c **** /* --- BDCR Register ---*/ + 45:stm32lib/src/stm32f10x_rcc.c **** /* Alias word address of RTCEN bit */ + 46:stm32lib/src/stm32f10x_rcc.c **** #define BDCR_OFFSET (RCC_OFFSET + 0x20) + 47:stm32lib/src/stm32f10x_rcc.c **** #define RTCEN_BitNumber 0x0F + 48:stm32lib/src/stm32f10x_rcc.c **** #define BDCR_RTCEN_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4)) + 49:stm32lib/src/stm32f10x_rcc.c **** + 50:stm32lib/src/stm32f10x_rcc.c **** /* Alias word address of BDRST bit */ + 51:stm32lib/src/stm32f10x_rcc.c **** #define BDRST_BitNumber 0x10 + 52:stm32lib/src/stm32f10x_rcc.c **** #define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4)) + 53:stm32lib/src/stm32f10x_rcc.c **** + 54:stm32lib/src/stm32f10x_rcc.c **** /* --- CSR Register ---*/ + 55:stm32lib/src/stm32f10x_rcc.c **** /* Alias word address of LSION bit */ + 56:stm32lib/src/stm32f10x_rcc.c **** #define CSR_OFFSET (RCC_OFFSET + 0x24) + 57:stm32lib/src/stm32f10x_rcc.c **** #define LSION_BitNumber 0x00 + 58:stm32lib/src/stm32f10x_rcc.c **** #define CSR_LSION_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4)) + 59:stm32lib/src/stm32f10x_rcc.c **** + 60:stm32lib/src/stm32f10x_rcc.c **** /* ---------------------- RCC registers bit mask ------------------------ */ + 61:stm32lib/src/stm32f10x_rcc.c **** /* CR register bit mask */ + 62:stm32lib/src/stm32f10x_rcc.c **** #define CR_HSEBYP_Reset ((u32)0xFFFBFFFF) + 63:stm32lib/src/stm32f10x_rcc.c **** #define CR_HSEBYP_Set ((u32)0x00040000) + 64:stm32lib/src/stm32f10x_rcc.c **** #define CR_HSEON_Reset ((u32)0xFFFEFFFF) + 65:stm32lib/src/stm32f10x_rcc.c **** #define CR_HSEON_Set ((u32)0x00010000) + 66:stm32lib/src/stm32f10x_rcc.c **** #define CR_HSITRIM_Mask ((u32)0xFFFFFF07) + 67:stm32lib/src/stm32f10x_rcc.c **** + 68:stm32lib/src/stm32f10x_rcc.c **** /* CFGR register bit mask */ + 69:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_PLL_Mask ((u32)0xFFC0FFFF) + 70:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_PLLMull_Mask ((u32)0x003C0000) + 71:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_PLLSRC_Mask ((u32)0x00010000) + 72:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_PLLXTPRE_Mask ((u32)0x00020000) + 73:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_SWS_Mask ((u32)0x0000000C) + 74:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_SW_Mask ((u32)0xFFFFFFFC) + 75:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_HPRE_Reset_Mask ((u32)0xFFFFFF0F) + 76:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_HPRE_Set_Mask ((u32)0x000000F0) + 77:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_PPRE1_Reset_Mask ((u32)0xFFFFF8FF) + 78:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_PPRE1_Set_Mask ((u32)0x00000700) + 79:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_PPRE2_Reset_Mask ((u32)0xFFFFC7FF) + 80:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_PPRE2_Set_Mask ((u32)0x00003800) + 81:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_ADCPRE_Reset_Mask ((u32)0xFFFF3FFF) + 82:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_ADCPRE_Set_Mask ((u32)0x0000C000) + 83:stm32lib/src/stm32f10x_rcc.c **** + 84:stm32lib/src/stm32f10x_rcc.c **** /* CSR register bit mask */ + 85:stm32lib/src/stm32f10x_rcc.c **** #define CSR_RMVF_Set ((u32)0x01000000) + 86:stm32lib/src/stm32f10x_rcc.c **** + 87:stm32lib/src/stm32f10x_rcc.c **** /* RCC Flag Mask */ + 88:stm32lib/src/stm32f10x_rcc.c **** #define FLAG_Mask ((u8)0x1F) + 89:stm32lib/src/stm32f10x_rcc.c **** + 90:stm32lib/src/stm32f10x_rcc.c **** /* Typical Value of the HSI in Hz */ + 91:stm32lib/src/stm32f10x_rcc.c **** #define HSI_Value ((u32)8000000) + 92:stm32lib/src/stm32f10x_rcc.c **** + 93:stm32lib/src/stm32f10x_rcc.c **** /* CIR register byte 2 (Bits[15:8]) base address */ + 94:stm32lib/src/stm32f10x_rcc.c **** #define CIR_BYTE2_ADDRESS ((u32)0x40021009) + 95:stm32lib/src/stm32f10x_rcc.c **** /* CIR register byte 3 (Bits[23:16]) base address */ + 96:stm32lib/src/stm32f10x_rcc.c **** #define CIR_BYTE3_ADDRESS ((u32)0x4002100A) + 97:stm32lib/src/stm32f10x_rcc.c **** + 98:stm32lib/src/stm32f10x_rcc.c **** /* CFGR register byte 4 (Bits[31:24]) base address */ + 99:stm32lib/src/stm32f10x_rcc.c **** #define CFGR_BYTE4_ADDRESS ((u32)0x40021007) + 100:stm32lib/src/stm32f10x_rcc.c **** + 101:stm32lib/src/stm32f10x_rcc.c **** /* BDCR register base address */ + 102:stm32lib/src/stm32f10x_rcc.c **** #define BDCR_ADDRESS (PERIPH_BASE + BDCR_OFFSET) + 103:stm32lib/src/stm32f10x_rcc.c **** + 104:stm32lib/src/stm32f10x_rcc.c **** /* Time out for HSE start up */ + 105:stm32lib/src/stm32f10x_rcc.c **** #define HSEStartUp_TimeOut ((u16)0x01FF) + 106:stm32lib/src/stm32f10x_rcc.c **** + 107:stm32lib/src/stm32f10x_rcc.c **** /* Private macro -------------------------------------------------------------*/ + 108:stm32lib/src/stm32f10x_rcc.c **** /* Private variables ---------------------------------------------------------*/ + 109:stm32lib/src/stm32f10x_rcc.c **** static uc8 APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9}; + 110:stm32lib/src/stm32f10x_rcc.c **** static uc8 ADCPrescTable[4] = {2, 4, 6, 8}; + 111:stm32lib/src/stm32f10x_rcc.c **** + 112:stm32lib/src/stm32f10x_rcc.c **** static volatile FlagStatus HSEStatus; + 113:stm32lib/src/stm32f10x_rcc.c **** static vu32 StartUpCounter = 0; + 114:stm32lib/src/stm32f10x_rcc.c **** + 115:stm32lib/src/stm32f10x_rcc.c **** /* Private function prototypes -----------------------------------------------*/ + 116:stm32lib/src/stm32f10x_rcc.c **** /* Private functions ---------------------------------------------------------*/ + 117:stm32lib/src/stm32f10x_rcc.c **** + 118:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 119:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_DeInit + 120:stm32lib/src/stm32f10x_rcc.c **** * Description : Resets the RCC clock configuration to the default reset state. + 121:stm32lib/src/stm32f10x_rcc.c **** * Input : None + 122:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 123:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 124:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 125:stm32lib/src/stm32f10x_rcc.c **** void RCC_DeInit(void) + 126:stm32lib/src/stm32f10x_rcc.c **** { + 30 .loc 1 126 0 + 31 @ args = 0, pretend = 0, frame = 0 + 32 @ frame_needed = 0, uses_anonymous_args = 0 + 33 @ link register save eliminated. + 127:stm32lib/src/stm32f10x_rcc.c **** /* Set HSION bit */ + 128:stm32lib/src/stm32f10x_rcc.c **** RCC->CR |= (u32)0x00000001; + 34 .loc 1 128 0 + 35 0000 0D4A ldr r2, .L3 + 36 0002 1368 ldr r3, [r2, #0] + 37 0004 43F00103 orr r3, r3, #1 + 38 0008 1360 str r3, [r2, #0] + 129:stm32lib/src/stm32f10x_rcc.c **** + 130:stm32lib/src/stm32f10x_rcc.c **** /* Reset SW[1:0], HPRE[3:0], PPRE1[2:0], PPRE2[2:0], ADCPRE[1:0] and MCO[2:0] bits */ + 131:stm32lib/src/stm32f10x_rcc.c **** RCC->CFGR &= (u32)0xF8FF0000; + 39 .loc 1 131 0 + 40 000a 5168 ldr r1, [r2, #4] + 41 000c 0B4B ldr r3, .L3+4 + 42 000e 01EA0303 and r3, r1, r3 + 43 0012 5360 str r3, [r2, #4] + 132:stm32lib/src/stm32f10x_rcc.c **** + 133:stm32lib/src/stm32f10x_rcc.c **** /* Reset HSEON, CSSON and PLLON bits */ + 134:stm32lib/src/stm32f10x_rcc.c **** RCC->CR &= (u32)0xFEF6FFFF; + 44 .loc 1 134 0 + 45 0014 1368 ldr r3, [r2, #0] + 46 0016 23F08473 bic r3, r3, #17301504 + 47 001a 23F48033 bic r3, r3, #65536 + 48 001e 1360 str r3, [r2, #0] + 135:stm32lib/src/stm32f10x_rcc.c **** + 136:stm32lib/src/stm32f10x_rcc.c **** /* Reset HSEBYP bit */ + 137:stm32lib/src/stm32f10x_rcc.c **** RCC->CR &= (u32)0xFFFBFFFF; + 49 .loc 1 137 0 + 50 0020 1368 ldr r3, [r2, #0] + 51 0022 23F48023 bic r3, r3, #262144 + 52 0026 1360 str r3, [r2, #0] + 138:stm32lib/src/stm32f10x_rcc.c **** + 139:stm32lib/src/stm32f10x_rcc.c **** /* Reset PLLSRC, PLLXTPRE, PLLMUL[3:0] and USBPRE bits */ + 140:stm32lib/src/stm32f10x_rcc.c **** RCC->CFGR &= (u32)0xFF80FFFF; + 53 .loc 1 140 0 + 54 0028 5368 ldr r3, [r2, #4] + 55 002a 23F4FE03 bic r3, r3, #8323072 + 56 002e 5360 str r3, [r2, #4] + 141:stm32lib/src/stm32f10x_rcc.c **** + 142:stm32lib/src/stm32f10x_rcc.c **** /* Disable all interrupts */ + 143:stm32lib/src/stm32f10x_rcc.c **** RCC->CIR = 0x00000000; + 57 .loc 1 143 0 + 58 0030 0023 movs r3, #0 + 59 0032 9360 str r3, [r2, #8] + 144:stm32lib/src/stm32f10x_rcc.c **** } + 60 .loc 1 144 0 + 61 0034 7047 bx lr + 62 .L4: + 63 0036 00BF .align 2 + 64 .L3: + 65 0038 00100240 .word 1073876992 + 66 003c 0000FFF8 .word -117506048 + 67 .LFE23: + 69 .align 2 + 70 .global RCC_HSEConfig + 71 .thumb + 72 .thumb_func + 74 RCC_HSEConfig: + 75 .LFB24: + 145:stm32lib/src/stm32f10x_rcc.c **** + 146:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 147:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_HSEConfig + 148:stm32lib/src/stm32f10x_rcc.c **** * Description : Configures the External High Speed oscillator (HSE). + 149:stm32lib/src/stm32f10x_rcc.c **** * HSE can not be stopped if it is used directly or through the + 150:stm32lib/src/stm32f10x_rcc.c **** * PLL as system clock. + 151:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_HSE: specifies the new state of the HSE. + 152:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be one of the following values: + 153:stm32lib/src/stm32f10x_rcc.c **** * - RCC_HSE_OFF: HSE oscillator OFF + 154:stm32lib/src/stm32f10x_rcc.c **** * - RCC_HSE_ON: HSE oscillator ON + 155:stm32lib/src/stm32f10x_rcc.c **** * - RCC_HSE_Bypass: HSE oscillator bypassed with external + 156:stm32lib/src/stm32f10x_rcc.c **** * clock + 157:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 158:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 159:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 160:stm32lib/src/stm32f10x_rcc.c **** void RCC_HSEConfig(u32 RCC_HSE) + 161:stm32lib/src/stm32f10x_rcc.c **** { + 76 .loc 1 161 0 + 77 @ args = 0, pretend = 0, frame = 0 + 78 @ frame_needed = 0, uses_anonymous_args = 0 + 79 @ link register save eliminated. + 80 .LVL0: + 162:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 163:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_HSE(RCC_HSE)); + 164:stm32lib/src/stm32f10x_rcc.c **** + 165:stm32lib/src/stm32f10x_rcc.c **** /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/ + 166:stm32lib/src/stm32f10x_rcc.c **** /* Reset HSEON bit */ + 167:stm32lib/src/stm32f10x_rcc.c **** RCC->CR &= CR_HSEON_Reset; + 81 .loc 1 167 0 + 82 0040 0C4A ldr r2, .L12 + 168:stm32lib/src/stm32f10x_rcc.c **** + 169:stm32lib/src/stm32f10x_rcc.c **** /* Reset HSEBYP bit */ + 170:stm32lib/src/stm32f10x_rcc.c **** RCC->CR &= CR_HSEBYP_Reset; + 171:stm32lib/src/stm32f10x_rcc.c **** + 172:stm32lib/src/stm32f10x_rcc.c **** /* Configure HSE (RCC_HSE_OFF is already covered by the code section above) */ + 173:stm32lib/src/stm32f10x_rcc.c **** switch(RCC_HSE) + 83 .loc 1 173 0 + 84 0042 B0F5803F cmp r0, #65536 + 85 .loc 1 167 0 + 86 0046 1368 ldr r3, [r2, #0] + 87 0048 23F48033 bic r3, r3, #65536 + 88 004c 1360 str r3, [r2, #0] + 89 .loc 1 170 0 + 90 004e 1368 ldr r3, [r2, #0] + 91 0050 23F48023 bic r3, r3, #262144 + 92 0054 1360 str r3, [r2, #0] + 93 .loc 1 173 0 + 94 0056 03D0 beq .L7 + 95 0058 B0F5802F cmp r0, #262144 + 96 005c 08D1 bne .L9 + 97 005e 03E0 b .L11 + 98 .L7: + 174:stm32lib/src/stm32f10x_rcc.c **** { + 175:stm32lib/src/stm32f10x_rcc.c **** case RCC_HSE_ON: + 176:stm32lib/src/stm32f10x_rcc.c **** /* Set HSEON bit */ + 177:stm32lib/src/stm32f10x_rcc.c **** RCC->CR |= CR_HSEON_Set; + 99 .loc 1 177 0 + 100 0060 1368 ldr r3, [r2, #0] + 101 0062 43F48033 orr r3, r3, #65536 + 102 0066 02E0 b .L10 + 103 .L11: + 178:stm32lib/src/stm32f10x_rcc.c **** break; + 179:stm32lib/src/stm32f10x_rcc.c **** + 180:stm32lib/src/stm32f10x_rcc.c **** case RCC_HSE_Bypass: + 181:stm32lib/src/stm32f10x_rcc.c **** /* Set HSEBYP and HSEON bits */ + 182:stm32lib/src/stm32f10x_rcc.c **** RCC->CR |= CR_HSEBYP_Set | CR_HSEON_Set; + 104 .loc 1 182 0 + 105 0068 1368 ldr r3, [r2, #0] + 106 006a 43F4A023 orr r3, r3, #327680 + 107 .L10: + 108 006e 1360 str r3, [r2, #0] + 109 .L9: + 183:stm32lib/src/stm32f10x_rcc.c **** break; + 184:stm32lib/src/stm32f10x_rcc.c **** + 185:stm32lib/src/stm32f10x_rcc.c **** default: + 186:stm32lib/src/stm32f10x_rcc.c **** break; + 187:stm32lib/src/stm32f10x_rcc.c **** } + 188:stm32lib/src/stm32f10x_rcc.c **** } + 110 .loc 1 188 0 + 111 0070 7047 bx lr + 112 .L13: + 113 0072 00BF .align 2 + 114 .L12: + 115 0074 00100240 .word 1073876992 + 116 .LFE24: + 118 .align 2 + 119 .global RCC_AdjustHSICalibrationValue + 120 .thumb + 121 .thumb_func + 123 RCC_AdjustHSICalibrationValue: + 124 .LFB26: + 189:stm32lib/src/stm32f10x_rcc.c **** + 190:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 191:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_WaitForHSEStartUp + 192:stm32lib/src/stm32f10x_rcc.c **** * Description : Waits for HSE start-up. + 193:stm32lib/src/stm32f10x_rcc.c **** * Input : None + 194:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 195:stm32lib/src/stm32f10x_rcc.c **** * Return : An ErrorStatus enumuration value: + 196:stm32lib/src/stm32f10x_rcc.c **** * - SUCCESS: HSE oscillator is stable and ready to use + 197:stm32lib/src/stm32f10x_rcc.c **** * - ERROR: HSE oscillator not yet ready + 198:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 199:stm32lib/src/stm32f10x_rcc.c **** ErrorStatus RCC_WaitForHSEStartUp(void) + 200:stm32lib/src/stm32f10x_rcc.c **** { + 201:stm32lib/src/stm32f10x_rcc.c **** ErrorStatus status = ERROR; + 202:stm32lib/src/stm32f10x_rcc.c **** + 203:stm32lib/src/stm32f10x_rcc.c **** /* Wait till HSE is ready and if Time out is reached exit */ + 204:stm32lib/src/stm32f10x_rcc.c **** do + 205:stm32lib/src/stm32f10x_rcc.c **** { + 206:stm32lib/src/stm32f10x_rcc.c **** HSEStatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY); + 207:stm32lib/src/stm32f10x_rcc.c **** StartUpCounter++; + 208:stm32lib/src/stm32f10x_rcc.c **** } while((HSEStatus == RESET) && (StartUpCounter != HSEStartUp_TimeOut)); + 209:stm32lib/src/stm32f10x_rcc.c **** + 210:stm32lib/src/stm32f10x_rcc.c **** + 211:stm32lib/src/stm32f10x_rcc.c **** if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET) + 212:stm32lib/src/stm32f10x_rcc.c **** { + 213:stm32lib/src/stm32f10x_rcc.c **** status = SUCCESS; + 214:stm32lib/src/stm32f10x_rcc.c **** } + 215:stm32lib/src/stm32f10x_rcc.c **** else + 216:stm32lib/src/stm32f10x_rcc.c **** { + 217:stm32lib/src/stm32f10x_rcc.c **** status = ERROR; + 218:stm32lib/src/stm32f10x_rcc.c **** } + 219:stm32lib/src/stm32f10x_rcc.c **** + 220:stm32lib/src/stm32f10x_rcc.c **** return (status); + 221:stm32lib/src/stm32f10x_rcc.c **** } + 222:stm32lib/src/stm32f10x_rcc.c **** + 223:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 224:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_AdjustHSICalibrationValue + 225:stm32lib/src/stm32f10x_rcc.c **** * Description : Adjusts the Internal High Speed oscillator (HSI) calibration + 226:stm32lib/src/stm32f10x_rcc.c **** * value. + 227:stm32lib/src/stm32f10x_rcc.c **** * Input : - HSICalibrationValue: specifies the calibration trimming value. + 228:stm32lib/src/stm32f10x_rcc.c **** * This parameter must be a number between 0 and 0x1F. + 229:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 230:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 231:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 232:stm32lib/src/stm32f10x_rcc.c **** void RCC_AdjustHSICalibrationValue(u8 HSICalibrationValue) + 233:stm32lib/src/stm32f10x_rcc.c **** { + 125 .loc 1 233 0 + 126 @ args = 0, pretend = 0, frame = 0 + 127 @ frame_needed = 0, uses_anonymous_args = 0 + 128 @ link register save eliminated. + 129 .LVL1: + 234:stm32lib/src/stm32f10x_rcc.c **** u32 tmpreg = 0; + 235:stm32lib/src/stm32f10x_rcc.c **** + 236:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 237:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_CALIBRATION_VALUE(HSICalibrationValue)); + 238:stm32lib/src/stm32f10x_rcc.c **** + 239:stm32lib/src/stm32f10x_rcc.c **** tmpreg = RCC->CR; + 130 .loc 1 239 0 + 131 0078 034A ldr r2, .L16 + 132 007a 1368 ldr r3, [r2, #0] + 133 .LVL2: + 240:stm32lib/src/stm32f10x_rcc.c **** + 241:stm32lib/src/stm32f10x_rcc.c **** /* Clear HSITRIM[4:0] bits */ + 242:stm32lib/src/stm32f10x_rcc.c **** tmpreg &= CR_HSITRIM_Mask; + 134 .loc 1 242 0 + 135 007c 23F0F803 bic r3, r3, #248 + 136 .LVL3: + 243:stm32lib/src/stm32f10x_rcc.c **** + 244:stm32lib/src/stm32f10x_rcc.c **** /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */ + 245:stm32lib/src/stm32f10x_rcc.c **** tmpreg |= (u32)HSICalibrationValue << 3; + 137 .loc 1 245 0 + 138 0080 43EAC003 orr r3, r3, r0, lsl #3 + 139 .LVL4: + 246:stm32lib/src/stm32f10x_rcc.c **** + 247:stm32lib/src/stm32f10x_rcc.c **** /* Store the new value */ + 248:stm32lib/src/stm32f10x_rcc.c **** RCC->CR = tmpreg; + 140 .loc 1 248 0 + 141 0084 1360 str r3, [r2, #0] + 249:stm32lib/src/stm32f10x_rcc.c **** } + 142 .loc 1 249 0 + 143 0086 7047 bx lr + 144 .L17: + 145 .align 2 + 146 .L16: + 147 0088 00100240 .word 1073876992 + 148 .LFE26: + 150 .align 2 + 151 .global RCC_HSICmd + 152 .thumb + 153 .thumb_func + 155 RCC_HSICmd: + 156 .LFB27: + 250:stm32lib/src/stm32f10x_rcc.c **** + 251:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 252:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_HSICmd + 253:stm32lib/src/stm32f10x_rcc.c **** * Description : Enables or disables the Internal High Speed oscillator (HSI). + 254:stm32lib/src/stm32f10x_rcc.c **** * HSI can not be stopped if it is used directly or through the + 255:stm32lib/src/stm32f10x_rcc.c **** * PLL as system clock. + 256:stm32lib/src/stm32f10x_rcc.c **** * Input : - NewState: new state of the HSI. + 257:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be: ENABLE or DISABLE. + 258:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 259:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 260:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 261:stm32lib/src/stm32f10x_rcc.c **** void RCC_HSICmd(FunctionalState NewState) + 262:stm32lib/src/stm32f10x_rcc.c **** { + 157 .loc 1 262 0 + 158 @ args = 0, pretend = 0, frame = 0 + 159 @ frame_needed = 0, uses_anonymous_args = 0 + 160 @ link register save eliminated. + 161 .LVL5: + 263:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 264:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 265:stm32lib/src/stm32f10x_rcc.c **** + 266:stm32lib/src/stm32f10x_rcc.c **** *(vu32 *) CR_HSION_BB = (u32)NewState; + 162 .loc 1 266 0 + 163 008c 014B ldr r3, .L20 + 164 008e 1860 str r0, [r3, #0] + 267:stm32lib/src/stm32f10x_rcc.c **** } + 165 .loc 1 267 0 + 166 0090 7047 bx lr + 167 .L21: + 168 0092 00BF .align 2 + 169 .L20: + 170 0094 00004242 .word 1111621632 + 171 .LFE27: + 173 .align 2 + 174 .global RCC_PLLConfig + 175 .thumb + 176 .thumb_func + 178 RCC_PLLConfig: + 179 .LFB28: + 268:stm32lib/src/stm32f10x_rcc.c **** + 269:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 270:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_PLLConfig + 271:stm32lib/src/stm32f10x_rcc.c **** * Description : Configures the PLL clock source and multiplication factor. + 272:stm32lib/src/stm32f10x_rcc.c **** * This function must be used only when the PLL is disabled. + 273:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_PLLSource: specifies the PLL entry clock source. + 274:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be one of the following values: + 275:stm32lib/src/stm32f10x_rcc.c **** * - RCC_PLLSource_HSI_Div2: HSI oscillator clock divided + 276:stm32lib/src/stm32f10x_rcc.c **** * by 2 selected as PLL clock entry + 277:stm32lib/src/stm32f10x_rcc.c **** * - RCC_PLLSource_HSE_Div1: HSE oscillator clock selected + 278:stm32lib/src/stm32f10x_rcc.c **** * as PLL clock entry + 279:stm32lib/src/stm32f10x_rcc.c **** * - RCC_PLLSource_HSE_Div2: HSE oscillator clock divided + 280:stm32lib/src/stm32f10x_rcc.c **** * by 2 selected as PLL clock entry + 281:stm32lib/src/stm32f10x_rcc.c **** * - RCC_PLLMul: specifies the PLL multiplication factor. + 282:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be RCC_PLLMul_x where x:[2,16] + 283:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 284:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 285:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 286:stm32lib/src/stm32f10x_rcc.c **** void RCC_PLLConfig(u32 RCC_PLLSource, u32 RCC_PLLMul) + 287:stm32lib/src/stm32f10x_rcc.c **** { + 180 .loc 1 287 0 + 181 @ args = 0, pretend = 0, frame = 0 + 182 @ frame_needed = 0, uses_anonymous_args = 0 + 183 @ link register save eliminated. + 184 .LVL6: + 288:stm32lib/src/stm32f10x_rcc.c **** u32 tmpreg = 0; + 289:stm32lib/src/stm32f10x_rcc.c **** + 290:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 291:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource)); + 292:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_PLL_MUL(RCC_PLLMul)); + 293:stm32lib/src/stm32f10x_rcc.c **** + 294:stm32lib/src/stm32f10x_rcc.c **** tmpreg = RCC->CFGR; + 185 .loc 1 294 0 + 186 0098 034B ldr r3, .L24 + 187 009a 5A68 ldr r2, [r3, #4] + 188 .LVL7: + 295:stm32lib/src/stm32f10x_rcc.c **** + 296:stm32lib/src/stm32f10x_rcc.c **** /* Clear PLLSRC, PLLXTPRE and PLLMUL[3:0] bits */ + 297:stm32lib/src/stm32f10x_rcc.c **** tmpreg &= CFGR_PLL_Mask; + 298:stm32lib/src/stm32f10x_rcc.c **** + 299:stm32lib/src/stm32f10x_rcc.c **** /* Set the PLL configuration bits */ + 300:stm32lib/src/stm32f10x_rcc.c **** tmpreg |= RCC_PLLSource | RCC_PLLMul; + 189 .loc 1 300 0 + 190 009c 22F47C12 bic r2, r2, #4128768 + 191 .LVL8: + 192 00a0 1043 orrs r0, r0, r2 + 193 .LVL9: + 194 00a2 0843 orrs r0, r0, r1 + 195 .LVL10: + 301:stm32lib/src/stm32f10x_rcc.c **** + 302:stm32lib/src/stm32f10x_rcc.c **** /* Store the new value */ + 303:stm32lib/src/stm32f10x_rcc.c **** RCC->CFGR = tmpreg; + 196 .loc 1 303 0 + 197 00a4 5860 str r0, [r3, #4] + 304:stm32lib/src/stm32f10x_rcc.c **** } + 198 .loc 1 304 0 + 199 00a6 7047 bx lr + 200 .L25: + 201 .align 2 + 202 .L24: + 203 00a8 00100240 .word 1073876992 + 204 .LFE28: + 206 .align 2 + 207 .global RCC_PLLCmd + 208 .thumb + 209 .thumb_func + 211 RCC_PLLCmd: + 212 .LFB29: + 305:stm32lib/src/stm32f10x_rcc.c **** + 306:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 307:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_PLLCmd + 308:stm32lib/src/stm32f10x_rcc.c **** * Description : Enables or disables the PLL. + 309:stm32lib/src/stm32f10x_rcc.c **** * The PLL can not be disabled if it is used as system clock. + 310:stm32lib/src/stm32f10x_rcc.c **** * Input : - NewState: new state of the PLL. + 311:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be: ENABLE or DISABLE. + 312:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 313:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 314:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 315:stm32lib/src/stm32f10x_rcc.c **** void RCC_PLLCmd(FunctionalState NewState) + 316:stm32lib/src/stm32f10x_rcc.c **** { + 213 .loc 1 316 0 + 214 @ args = 0, pretend = 0, frame = 0 + 215 @ frame_needed = 0, uses_anonymous_args = 0 + 216 @ link register save eliminated. + 217 .LVL11: + 317:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 318:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 319:stm32lib/src/stm32f10x_rcc.c **** + 320:stm32lib/src/stm32f10x_rcc.c **** *(vu32 *) CR_PLLON_BB = (u32)NewState; + 218 .loc 1 320 0 + 219 00ac 014B ldr r3, .L28 + 220 00ae 1860 str r0, [r3, #0] + 321:stm32lib/src/stm32f10x_rcc.c **** } + 221 .loc 1 321 0 + 222 00b0 7047 bx lr + 223 .L29: + 224 00b2 00BF .align 2 + 225 .L28: + 226 00b4 60004242 .word 1111621728 + 227 .LFE29: + 229 .align 2 + 230 .global RCC_SYSCLKConfig + 231 .thumb + 232 .thumb_func + 234 RCC_SYSCLKConfig: + 235 .LFB30: + 322:stm32lib/src/stm32f10x_rcc.c **** + 323:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 324:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_SYSCLKConfig + 325:stm32lib/src/stm32f10x_rcc.c **** * Description : Configures the system clock (SYSCLK). + 326:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_SYSCLKSource: specifies the clock source used as system + 327:stm32lib/src/stm32f10x_rcc.c **** * clock. This parameter can be one of the following values: + 328:stm32lib/src/stm32f10x_rcc.c **** * - RCC_SYSCLKSource_HSI: HSI selected as system clock + 329:stm32lib/src/stm32f10x_rcc.c **** * - RCC_SYSCLKSource_HSE: HSE selected as system clock + 330:stm32lib/src/stm32f10x_rcc.c **** * - RCC_SYSCLKSource_PLLCLK: PLL selected as system clock + 331:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 332:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 333:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 334:stm32lib/src/stm32f10x_rcc.c **** void RCC_SYSCLKConfig(u32 RCC_SYSCLKSource) + 335:stm32lib/src/stm32f10x_rcc.c **** { + 236 .loc 1 335 0 + 237 @ args = 0, pretend = 0, frame = 0 + 238 @ frame_needed = 0, uses_anonymous_args = 0 + 239 @ link register save eliminated. + 240 .LVL12: + 336:stm32lib/src/stm32f10x_rcc.c **** u32 tmpreg = 0; + 337:stm32lib/src/stm32f10x_rcc.c **** + 338:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 339:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource)); + 340:stm32lib/src/stm32f10x_rcc.c **** + 341:stm32lib/src/stm32f10x_rcc.c **** tmpreg = RCC->CFGR; + 241 .loc 1 341 0 + 242 00b8 034B ldr r3, .L32 + 243 00ba 5A68 ldr r2, [r3, #4] + 244 .LVL13: + 342:stm32lib/src/stm32f10x_rcc.c **** + 343:stm32lib/src/stm32f10x_rcc.c **** /* Clear SW[1:0] bits */ + 344:stm32lib/src/stm32f10x_rcc.c **** tmpreg &= CFGR_SW_Mask; + 245 .loc 1 344 0 + 246 00bc 22F00302 bic r2, r2, #3 + 247 .LVL14: + 345:stm32lib/src/stm32f10x_rcc.c **** + 346:stm32lib/src/stm32f10x_rcc.c **** /* Set SW[1:0] bits according to RCC_SYSCLKSource value */ + 347:stm32lib/src/stm32f10x_rcc.c **** tmpreg |= RCC_SYSCLKSource; + 248 .loc 1 347 0 + 249 00c0 1043 orrs r0, r0, r2 + 250 .LVL15: + 348:stm32lib/src/stm32f10x_rcc.c **** + 349:stm32lib/src/stm32f10x_rcc.c **** /* Store the new value */ + 350:stm32lib/src/stm32f10x_rcc.c **** RCC->CFGR = tmpreg; + 251 .loc 1 350 0 + 252 00c2 5860 str r0, [r3, #4] + 351:stm32lib/src/stm32f10x_rcc.c **** } + 253 .loc 1 351 0 + 254 00c4 7047 bx lr + 255 .L33: + 256 00c6 00BF .align 2 + 257 .L32: + 258 00c8 00100240 .word 1073876992 + 259 .LFE30: + 261 .align 2 + 262 .global RCC_GetSYSCLKSource + 263 .thumb + 264 .thumb_func + 266 RCC_GetSYSCLKSource: + 267 .LFB31: + 352:stm32lib/src/stm32f10x_rcc.c **** + 353:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 354:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_GetSYSCLKSource + 355:stm32lib/src/stm32f10x_rcc.c **** * Description : Returns the clock source used as system clock. + 356:stm32lib/src/stm32f10x_rcc.c **** * Input : None + 357:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 358:stm32lib/src/stm32f10x_rcc.c **** * Return : The clock source used as system clock. The returned value can + 359:stm32lib/src/stm32f10x_rcc.c **** * be one of the following: + 360:stm32lib/src/stm32f10x_rcc.c **** * - 0x00: HSI used as system clock + 361:stm32lib/src/stm32f10x_rcc.c **** * - 0x04: HSE used as system clock + 362:stm32lib/src/stm32f10x_rcc.c **** * - 0x08: PLL used as system clock + 363:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 364:stm32lib/src/stm32f10x_rcc.c **** u8 RCC_GetSYSCLKSource(void) + 365:stm32lib/src/stm32f10x_rcc.c **** { + 268 .loc 1 365 0 + 269 @ args = 0, pretend = 0, frame = 0 + 270 @ frame_needed = 0, uses_anonymous_args = 0 + 271 @ link register save eliminated. + 366:stm32lib/src/stm32f10x_rcc.c **** return ((u8)(RCC->CFGR & CFGR_SWS_Mask)); + 272 .loc 1 366 0 + 273 00cc 024B ldr r3, .L36 + 274 00ce 5868 ldr r0, [r3, #4] + 367:stm32lib/src/stm32f10x_rcc.c **** } + 275 .loc 1 367 0 + 276 00d0 00F00C00 and r0, r0, #12 + 277 00d4 7047 bx lr + 278 .L37: + 279 00d6 00BF .align 2 + 280 .L36: + 281 00d8 00100240 .word 1073876992 + 282 .LFE31: + 284 .align 2 + 285 .global RCC_HCLKConfig + 286 .thumb + 287 .thumb_func + 289 RCC_HCLKConfig: + 290 .LFB32: + 368:stm32lib/src/stm32f10x_rcc.c **** + 369:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 370:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_HCLKConfig + 371:stm32lib/src/stm32f10x_rcc.c **** * Description : Configures the AHB clock (HCLK). + 372:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_SYSCLK: defines the AHB clock divider. This clock is + 373:stm32lib/src/stm32f10x_rcc.c **** * derived from the system clock (SYSCLK). + 374:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be one of the following values: + 375:stm32lib/src/stm32f10x_rcc.c **** * - RCC_SYSCLK_Div1: AHB clock = SYSCLK + 376:stm32lib/src/stm32f10x_rcc.c **** * - RCC_SYSCLK_Div2: AHB clock = SYSCLK/2 + 377:stm32lib/src/stm32f10x_rcc.c **** * - RCC_SYSCLK_Div4: AHB clock = SYSCLK/4 + 378:stm32lib/src/stm32f10x_rcc.c **** * - RCC_SYSCLK_Div8: AHB clock = SYSCLK/8 + 379:stm32lib/src/stm32f10x_rcc.c **** * - RCC_SYSCLK_Div16: AHB clock = SYSCLK/16 + 380:stm32lib/src/stm32f10x_rcc.c **** * - RCC_SYSCLK_Div64: AHB clock = SYSCLK/64 + 381:stm32lib/src/stm32f10x_rcc.c **** * - RCC_SYSCLK_Div128: AHB clock = SYSCLK/128 + 382:stm32lib/src/stm32f10x_rcc.c **** * - RCC_SYSCLK_Div256: AHB clock = SYSCLK/256 + 383:stm32lib/src/stm32f10x_rcc.c **** * - RCC_SYSCLK_Div512: AHB clock = SYSCLK/512 + 384:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 385:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 386:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 387:stm32lib/src/stm32f10x_rcc.c **** void RCC_HCLKConfig(u32 RCC_SYSCLK) + 388:stm32lib/src/stm32f10x_rcc.c **** { + 291 .loc 1 388 0 + 292 @ args = 0, pretend = 0, frame = 0 + 293 @ frame_needed = 0, uses_anonymous_args = 0 + 294 @ link register save eliminated. + 295 .LVL16: + 389:stm32lib/src/stm32f10x_rcc.c **** u32 tmpreg = 0; + 390:stm32lib/src/stm32f10x_rcc.c **** + 391:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 392:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_HCLK(RCC_SYSCLK)); + 393:stm32lib/src/stm32f10x_rcc.c **** + 394:stm32lib/src/stm32f10x_rcc.c **** tmpreg = RCC->CFGR; + 296 .loc 1 394 0 + 297 00dc 034B ldr r3, .L40 + 298 00de 5A68 ldr r2, [r3, #4] + 299 .LVL17: + 395:stm32lib/src/stm32f10x_rcc.c **** + 396:stm32lib/src/stm32f10x_rcc.c **** /* Clear HPRE[3:0] bits */ + 397:stm32lib/src/stm32f10x_rcc.c **** tmpreg &= CFGR_HPRE_Reset_Mask; + 300 .loc 1 397 0 + 301 00e0 22F0F002 bic r2, r2, #240 + 302 .LVL18: + 398:stm32lib/src/stm32f10x_rcc.c **** + 399:stm32lib/src/stm32f10x_rcc.c **** /* Set HPRE[3:0] bits according to RCC_SYSCLK value */ + 400:stm32lib/src/stm32f10x_rcc.c **** tmpreg |= RCC_SYSCLK; + 303 .loc 1 400 0 + 304 00e4 1043 orrs r0, r0, r2 + 305 .LVL19: + 401:stm32lib/src/stm32f10x_rcc.c **** + 402:stm32lib/src/stm32f10x_rcc.c **** /* Store the new value */ + 403:stm32lib/src/stm32f10x_rcc.c **** RCC->CFGR = tmpreg; + 306 .loc 1 403 0 + 307 00e6 5860 str r0, [r3, #4] + 404:stm32lib/src/stm32f10x_rcc.c **** } + 308 .loc 1 404 0 + 309 00e8 7047 bx lr + 310 .L41: + 311 00ea 00BF .align 2 + 312 .L40: + 313 00ec 00100240 .word 1073876992 + 314 .LFE32: + 316 .align 2 + 317 .global RCC_PCLK1Config + 318 .thumb + 319 .thumb_func + 321 RCC_PCLK1Config: + 322 .LFB33: + 405:stm32lib/src/stm32f10x_rcc.c **** + 406:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 407:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_PCLK1Config + 408:stm32lib/src/stm32f10x_rcc.c **** * Description : Configures the Low Speed APB clock (PCLK1). + 409:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_HCLK: defines the APB1 clock divider. This clock is + 410:stm32lib/src/stm32f10x_rcc.c **** * derived from the AHB clock (HCLK). + 411:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be one of the following values: + 412:stm32lib/src/stm32f10x_rcc.c **** * - RCC_HCLK_Div1: APB1 clock = HCLK + 413:stm32lib/src/stm32f10x_rcc.c **** * - RCC_HCLK_Div2: APB1 clock = HCLK/2 + 414:stm32lib/src/stm32f10x_rcc.c **** * - RCC_HCLK_Div4: APB1 clock = HCLK/4 + 415:stm32lib/src/stm32f10x_rcc.c **** * - RCC_HCLK_Div8: APB1 clock = HCLK/8 + 416:stm32lib/src/stm32f10x_rcc.c **** * - RCC_HCLK_Div16: APB1 clock = HCLK/16 + 417:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 418:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 419:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 420:stm32lib/src/stm32f10x_rcc.c **** void RCC_PCLK1Config(u32 RCC_HCLK) + 421:stm32lib/src/stm32f10x_rcc.c **** { + 323 .loc 1 421 0 + 324 @ args = 0, pretend = 0, frame = 0 + 325 @ frame_needed = 0, uses_anonymous_args = 0 + 326 @ link register save eliminated. + 327 .LVL20: + 422:stm32lib/src/stm32f10x_rcc.c **** u32 tmpreg = 0; + 423:stm32lib/src/stm32f10x_rcc.c **** + 424:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 425:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_PCLK(RCC_HCLK)); + 426:stm32lib/src/stm32f10x_rcc.c **** + 427:stm32lib/src/stm32f10x_rcc.c **** tmpreg = RCC->CFGR; + 328 .loc 1 427 0 + 329 00f0 034B ldr r3, .L44 + 330 00f2 5A68 ldr r2, [r3, #4] + 331 .LVL21: + 428:stm32lib/src/stm32f10x_rcc.c **** + 429:stm32lib/src/stm32f10x_rcc.c **** /* Clear PPRE1[2:0] bits */ + 430:stm32lib/src/stm32f10x_rcc.c **** tmpreg &= CFGR_PPRE1_Reset_Mask; + 332 .loc 1 430 0 + 333 00f4 22F4E062 bic r2, r2, #1792 + 334 .LVL22: + 431:stm32lib/src/stm32f10x_rcc.c **** + 432:stm32lib/src/stm32f10x_rcc.c **** /* Set PPRE1[2:0] bits according to RCC_HCLK value */ + 433:stm32lib/src/stm32f10x_rcc.c **** tmpreg |= RCC_HCLK; + 335 .loc 1 433 0 + 336 00f8 1043 orrs r0, r0, r2 + 337 .LVL23: + 434:stm32lib/src/stm32f10x_rcc.c **** + 435:stm32lib/src/stm32f10x_rcc.c **** /* Store the new value */ + 436:stm32lib/src/stm32f10x_rcc.c **** RCC->CFGR = tmpreg; + 338 .loc 1 436 0 + 339 00fa 5860 str r0, [r3, #4] + 437:stm32lib/src/stm32f10x_rcc.c **** } + 340 .loc 1 437 0 + 341 00fc 7047 bx lr + 342 .L45: + 343 00fe 00BF .align 2 + 344 .L44: + 345 0100 00100240 .word 1073876992 + 346 .LFE33: + 348 .align 2 + 349 .global RCC_PCLK2Config + 350 .thumb + 351 .thumb_func + 353 RCC_PCLK2Config: + 354 .LFB34: + 438:stm32lib/src/stm32f10x_rcc.c **** + 439:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 440:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_PCLK2Config + 441:stm32lib/src/stm32f10x_rcc.c **** * Description : Configures the High Speed APB clock (PCLK2). + 442:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_HCLK: defines the APB2 clock divider. This clock is + 443:stm32lib/src/stm32f10x_rcc.c **** * derived from the AHB clock (HCLK). + 444:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be one of the following values: + 445:stm32lib/src/stm32f10x_rcc.c **** * - RCC_HCLK_Div1: APB2 clock = HCLK + 446:stm32lib/src/stm32f10x_rcc.c **** * - RCC_HCLK_Div2: APB2 clock = HCLK/2 + 447:stm32lib/src/stm32f10x_rcc.c **** * - RCC_HCLK_Div4: APB2 clock = HCLK/4 + 448:stm32lib/src/stm32f10x_rcc.c **** * - RCC_HCLK_Div8: APB2 clock = HCLK/8 + 449:stm32lib/src/stm32f10x_rcc.c **** * - RCC_HCLK_Div16: APB2 clock = HCLK/16 + 450:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 451:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 452:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 453:stm32lib/src/stm32f10x_rcc.c **** void RCC_PCLK2Config(u32 RCC_HCLK) + 454:stm32lib/src/stm32f10x_rcc.c **** { + 355 .loc 1 454 0 + 356 @ args = 0, pretend = 0, frame = 0 + 357 @ frame_needed = 0, uses_anonymous_args = 0 + 358 @ link register save eliminated. + 359 .LVL24: + 455:stm32lib/src/stm32f10x_rcc.c **** u32 tmpreg = 0; + 456:stm32lib/src/stm32f10x_rcc.c **** + 457:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 458:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_PCLK(RCC_HCLK)); + 459:stm32lib/src/stm32f10x_rcc.c **** + 460:stm32lib/src/stm32f10x_rcc.c **** tmpreg = RCC->CFGR; + 360 .loc 1 460 0 + 361 0104 034A ldr r2, .L48 + 362 0106 5368 ldr r3, [r2, #4] + 363 .LVL25: + 461:stm32lib/src/stm32f10x_rcc.c **** + 462:stm32lib/src/stm32f10x_rcc.c **** /* Clear PPRE2[2:0] bits */ + 463:stm32lib/src/stm32f10x_rcc.c **** tmpreg &= CFGR_PPRE2_Reset_Mask; + 364 .loc 1 463 0 + 365 0108 23F46053 bic r3, r3, #14336 + 366 .LVL26: + 464:stm32lib/src/stm32f10x_rcc.c **** + 465:stm32lib/src/stm32f10x_rcc.c **** /* Set PPRE2[2:0] bits according to RCC_HCLK value */ + 466:stm32lib/src/stm32f10x_rcc.c **** tmpreg |= RCC_HCLK << 3; + 367 .loc 1 466 0 + 368 010c 43EAC003 orr r3, r3, r0, lsl #3 + 369 .LVL27: + 467:stm32lib/src/stm32f10x_rcc.c **** + 468:stm32lib/src/stm32f10x_rcc.c **** /* Store the new value */ + 469:stm32lib/src/stm32f10x_rcc.c **** RCC->CFGR = tmpreg; + 370 .loc 1 469 0 + 371 0110 5360 str r3, [r2, #4] + 470:stm32lib/src/stm32f10x_rcc.c **** } + 372 .loc 1 470 0 + 373 0112 7047 bx lr + 374 .L49: + 375 .align 2 + 376 .L48: + 377 0114 00100240 .word 1073876992 + 378 .LFE34: + 380 .align 2 + 381 .global RCC_ITConfig + 382 .thumb + 383 .thumb_func + 385 RCC_ITConfig: + 386 .LFB35: + 471:stm32lib/src/stm32f10x_rcc.c **** + 472:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 473:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_ITConfig + 474:stm32lib/src/stm32f10x_rcc.c **** * Description : Enables or disables the specified RCC interrupts. + 475:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_IT: specifies the RCC interrupt sources to be enabled + 476:stm32lib/src/stm32f10x_rcc.c **** * or disabled. + 477:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be any combination of the following values: + 478:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_LSIRDY: LSI ready interrupt + 479:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_LSERDY: LSE ready interrupt + 480:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_HSIRDY: HSI ready interrupt + 481:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_HSERDY: HSE ready interrupt + 482:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_PLLRDY: PLL ready interrupt + 483:stm32lib/src/stm32f10x_rcc.c **** * - NewState: new state of the specified RCC interrupts. + 484:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be: ENABLE or DISABLE. + 485:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 486:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 487:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 488:stm32lib/src/stm32f10x_rcc.c **** void RCC_ITConfig(u8 RCC_IT, FunctionalState NewState) + 489:stm32lib/src/stm32f10x_rcc.c **** { + 387 .loc 1 489 0 + 388 @ args = 0, pretend = 0, frame = 0 + 389 @ frame_needed = 0, uses_anonymous_args = 0 + 390 @ link register save eliminated. + 391 .LVL28: + 490:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 491:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_IT(RCC_IT)); + 492:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 493:stm32lib/src/stm32f10x_rcc.c **** + 494:stm32lib/src/stm32f10x_rcc.c **** if (NewState != DISABLE) + 392 .loc 1 494 0 + 393 0118 21B1 cbz r1, .L51 + 495:stm32lib/src/stm32f10x_rcc.c **** { + 496:stm32lib/src/stm32f10x_rcc.c **** /* Perform Byte access to RCC_CIR[12:8] bits to enable the selected interrupts */ + 497:stm32lib/src/stm32f10x_rcc.c **** *(vu8 *) CIR_BYTE2_ADDRESS |= RCC_IT; + 394 .loc 1 497 0 + 395 011a 054A ldr r2, .L55 + 396 011c 1378 ldrb r3, [r2, #0] @ zero_extendqisi2 + 397 011e 40EA0303 orr r3, r0, r3 + 398 0122 03E0 b .L54 + 399 .L51: + 498:stm32lib/src/stm32f10x_rcc.c **** } + 499:stm32lib/src/stm32f10x_rcc.c **** else + 500:stm32lib/src/stm32f10x_rcc.c **** { + 501:stm32lib/src/stm32f10x_rcc.c **** /* Perform Byte access to RCC_CIR[12:8] bits to disable the selected interrupts */ + 502:stm32lib/src/stm32f10x_rcc.c **** *(vu8 *) CIR_BYTE2_ADDRESS &= (u8)~RCC_IT; + 400 .loc 1 502 0 + 401 0124 024A ldr r2, .L55 + 402 0126 1378 ldrb r3, [r2, #0] @ zero_extendqisi2 + 403 0128 23EA0003 bic r3, r3, r0 + 404 .L54: + 405 012c 1370 strb r3, [r2, #0] + 503:stm32lib/src/stm32f10x_rcc.c **** } + 504:stm32lib/src/stm32f10x_rcc.c **** } + 406 .loc 1 504 0 + 407 012e 7047 bx lr + 408 .L56: + 409 .align 2 + 410 .L55: + 411 0130 09100240 .word 1073877001 + 412 .LFE35: + 414 .align 2 + 415 .global RCC_USBCLKConfig + 416 .thumb + 417 .thumb_func + 419 RCC_USBCLKConfig: + 420 .LFB36: + 505:stm32lib/src/stm32f10x_rcc.c **** + 506:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 507:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_USBCLKConfig + 508:stm32lib/src/stm32f10x_rcc.c **** * Description : Configures the USB clock (USBCLK). + 509:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_USBCLKSource: specifies the USB clock source. This clock + 510:stm32lib/src/stm32f10x_rcc.c **** * is derived from the PLL output. + 511:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be one of the following values: + 512:stm32lib/src/stm32f10x_rcc.c **** * - RCC_USBCLKSource_PLLCLK_1Div5: PLL clock divided by 1,5 + 513:stm32lib/src/stm32f10x_rcc.c **** * selected as USB clock source + 514:stm32lib/src/stm32f10x_rcc.c **** * - RCC_USBCLKSource_PLLCLK_Div1: PLL clock selected as USB + 515:stm32lib/src/stm32f10x_rcc.c **** * clock source + 516:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 517:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 518:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 519:stm32lib/src/stm32f10x_rcc.c **** void RCC_USBCLKConfig(u32 RCC_USBCLKSource) + 520:stm32lib/src/stm32f10x_rcc.c **** { + 421 .loc 1 520 0 + 422 @ args = 0, pretend = 0, frame = 0 + 423 @ frame_needed = 0, uses_anonymous_args = 0 + 424 @ link register save eliminated. + 425 .LVL29: + 521:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 522:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_USBCLK_SOURCE(RCC_USBCLKSource)); + 523:stm32lib/src/stm32f10x_rcc.c **** + 524:stm32lib/src/stm32f10x_rcc.c **** *(vu32 *) CFGR_USBPRE_BB = RCC_USBCLKSource; + 426 .loc 1 524 0 + 427 0134 014B ldr r3, .L59 + 428 0136 1860 str r0, [r3, #0] + 525:stm32lib/src/stm32f10x_rcc.c **** } + 429 .loc 1 525 0 + 430 0138 7047 bx lr + 431 .L60: + 432 013a 00BF .align 2 + 433 .L59: + 434 013c D8004242 .word 1111621848 + 435 .LFE36: + 437 .align 2 + 438 .global RCC_ADCCLKConfig + 439 .thumb + 440 .thumb_func + 442 RCC_ADCCLKConfig: + 443 .LFB37: + 526:stm32lib/src/stm32f10x_rcc.c **** + 527:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 528:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_ADCCLKConfig + 529:stm32lib/src/stm32f10x_rcc.c **** * Description : Configures the ADC clock (ADCCLK). + 530:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_PCLK2: defines the ADC clock divider. This clock is + 531:stm32lib/src/stm32f10x_rcc.c **** * derived from the APB2 clock (PCLK2). + 532:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be one of the following values: + 533:stm32lib/src/stm32f10x_rcc.c **** * - RCC_PCLK2_Div2: ADC clock = PCLK2/2 + 534:stm32lib/src/stm32f10x_rcc.c **** * - RCC_PCLK2_Div4: ADC clock = PCLK2/4 + 535:stm32lib/src/stm32f10x_rcc.c **** * - RCC_PCLK2_Div6: ADC clock = PCLK2/6 + 536:stm32lib/src/stm32f10x_rcc.c **** * - RCC_PCLK2_Div8: ADC clock = PCLK2/8 + 537:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 538:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 539:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 540:stm32lib/src/stm32f10x_rcc.c **** void RCC_ADCCLKConfig(u32 RCC_PCLK2) + 541:stm32lib/src/stm32f10x_rcc.c **** { + 444 .loc 1 541 0 + 445 @ args = 0, pretend = 0, frame = 0 + 446 @ frame_needed = 0, uses_anonymous_args = 0 + 447 @ link register save eliminated. + 448 .LVL30: + 542:stm32lib/src/stm32f10x_rcc.c **** u32 tmpreg = 0; + 543:stm32lib/src/stm32f10x_rcc.c **** + 544:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 545:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_ADCCLK(RCC_PCLK2)); + 546:stm32lib/src/stm32f10x_rcc.c **** + 547:stm32lib/src/stm32f10x_rcc.c **** tmpreg = RCC->CFGR; + 449 .loc 1 547 0 + 450 0140 034B ldr r3, .L63 + 451 0142 5A68 ldr r2, [r3, #4] + 452 .LVL31: + 548:stm32lib/src/stm32f10x_rcc.c **** + 549:stm32lib/src/stm32f10x_rcc.c **** /* Clear ADCPRE[1:0] bits */ + 550:stm32lib/src/stm32f10x_rcc.c **** tmpreg &= CFGR_ADCPRE_Reset_Mask; + 453 .loc 1 550 0 + 454 0144 22F44042 bic r2, r2, #49152 + 455 .LVL32: + 551:stm32lib/src/stm32f10x_rcc.c **** + 552:stm32lib/src/stm32f10x_rcc.c **** /* Set ADCPRE[1:0] bits according to RCC_PCLK2 value */ + 553:stm32lib/src/stm32f10x_rcc.c **** tmpreg |= RCC_PCLK2; + 456 .loc 1 553 0 + 457 0148 1043 orrs r0, r0, r2 + 458 .LVL33: + 554:stm32lib/src/stm32f10x_rcc.c **** + 555:stm32lib/src/stm32f10x_rcc.c **** /* Store the new value */ + 556:stm32lib/src/stm32f10x_rcc.c **** RCC->CFGR = tmpreg; + 459 .loc 1 556 0 + 460 014a 5860 str r0, [r3, #4] + 557:stm32lib/src/stm32f10x_rcc.c **** } + 461 .loc 1 557 0 + 462 014c 7047 bx lr + 463 .L64: + 464 014e 00BF .align 2 + 465 .L63: + 466 0150 00100240 .word 1073876992 + 467 .LFE37: + 469 .align 2 + 470 .global RCC_LSEConfig + 471 .thumb + 472 .thumb_func + 474 RCC_LSEConfig: + 475 .LFB38: + 558:stm32lib/src/stm32f10x_rcc.c **** + 559:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 560:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_LSEConfig + 561:stm32lib/src/stm32f10x_rcc.c **** * Description : Configures the External Low Speed oscillator (LSE). + 562:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_LSE: specifies the new state of the LSE. + 563:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be one of the following values: + 564:stm32lib/src/stm32f10x_rcc.c **** * - RCC_LSE_OFF: LSE oscillator OFF + 565:stm32lib/src/stm32f10x_rcc.c **** * - RCC_LSE_ON: LSE oscillator ON + 566:stm32lib/src/stm32f10x_rcc.c **** * - RCC_LSE_Bypass: LSE oscillator bypassed with external + 567:stm32lib/src/stm32f10x_rcc.c **** * clock + 568:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 569:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 570:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 571:stm32lib/src/stm32f10x_rcc.c **** void RCC_LSEConfig(u8 RCC_LSE) + 572:stm32lib/src/stm32f10x_rcc.c **** { + 476 .loc 1 572 0 + 477 @ args = 0, pretend = 0, frame = 0 + 478 @ frame_needed = 0, uses_anonymous_args = 0 + 479 @ link register save eliminated. + 480 .LVL34: + 573:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 574:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_LSE(RCC_LSE)); + 575:stm32lib/src/stm32f10x_rcc.c **** + 576:stm32lib/src/stm32f10x_rcc.c **** /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/ + 577:stm32lib/src/stm32f10x_rcc.c **** /* Reset LSEON bit */ + 578:stm32lib/src/stm32f10x_rcc.c **** *(vu8 *) BDCR_ADDRESS = RCC_LSE_OFF; + 481 .loc 1 578 0 + 482 0154 064A ldr r2, .L71 + 483 0156 0023 movs r3, #0 + 579:stm32lib/src/stm32f10x_rcc.c **** + 580:stm32lib/src/stm32f10x_rcc.c **** /* Reset LSEBYP bit */ + 581:stm32lib/src/stm32f10x_rcc.c **** *(vu8 *) BDCR_ADDRESS = RCC_LSE_OFF; + 582:stm32lib/src/stm32f10x_rcc.c **** + 583:stm32lib/src/stm32f10x_rcc.c **** /* Configure LSE (RCC_LSE_OFF is already covered by the code section above) */ + 584:stm32lib/src/stm32f10x_rcc.c **** switch(RCC_LSE) + 484 .loc 1 584 0 + 485 0158 0128 cmp r0, #1 + 486 .loc 1 578 0 + 487 015a 1370 strb r3, [r2, #0] + 488 .loc 1 581 0 + 489 015c 1370 strb r3, [r2, #0] + 490 .loc 1 584 0 + 491 015e 02D0 beq .L67 + 492 0160 0428 cmp r0, #4 + 493 0162 04D1 bne .L69 + 494 0164 01E0 b .L70 + 495 .L67: + 585:stm32lib/src/stm32f10x_rcc.c **** { + 586:stm32lib/src/stm32f10x_rcc.c **** case RCC_LSE_ON: + 587:stm32lib/src/stm32f10x_rcc.c **** /* Set LSEON bit */ + 588:stm32lib/src/stm32f10x_rcc.c **** *(vu8 *) BDCR_ADDRESS = RCC_LSE_ON; + 496 .loc 1 588 0 + 497 0166 1070 strb r0, [r2, #0] + 498 0168 01E0 b .L69 + 499 .L70: + 589:stm32lib/src/stm32f10x_rcc.c **** break; + 590:stm32lib/src/stm32f10x_rcc.c **** + 591:stm32lib/src/stm32f10x_rcc.c **** case RCC_LSE_Bypass: + 592:stm32lib/src/stm32f10x_rcc.c **** /* Set LSEBYP and LSEON bits */ + 593:stm32lib/src/stm32f10x_rcc.c **** *(vu8 *) BDCR_ADDRESS = RCC_LSE_Bypass | RCC_LSE_ON; + 500 .loc 1 593 0 + 501 016a 0523 movs r3, #5 + 502 016c 1370 strb r3, [r2, #0] + 503 .L69: + 594:stm32lib/src/stm32f10x_rcc.c **** break; + 595:stm32lib/src/stm32f10x_rcc.c **** + 596:stm32lib/src/stm32f10x_rcc.c **** default: + 597:stm32lib/src/stm32f10x_rcc.c **** break; + 598:stm32lib/src/stm32f10x_rcc.c **** } + 599:stm32lib/src/stm32f10x_rcc.c **** } + 504 .loc 1 599 0 + 505 016e 7047 bx lr + 506 .L72: + 507 .align 2 + 508 .L71: + 509 0170 20100240 .word 1073877024 + 510 .LFE38: + 512 .align 2 + 513 .global RCC_LSICmd + 514 .thumb + 515 .thumb_func + 517 RCC_LSICmd: + 518 .LFB39: + 600:stm32lib/src/stm32f10x_rcc.c **** + 601:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 602:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_LSICmd + 603:stm32lib/src/stm32f10x_rcc.c **** * Description : Enables or disables the Internal Low Speed oscillator (LSI). + 604:stm32lib/src/stm32f10x_rcc.c **** * LSI can not be disabled if the IWDG is running. + 605:stm32lib/src/stm32f10x_rcc.c **** * Input : - NewState: new state of the LSI. + 606:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be: ENABLE or DISABLE. + 607:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 608:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 609:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 610:stm32lib/src/stm32f10x_rcc.c **** void RCC_LSICmd(FunctionalState NewState) + 611:stm32lib/src/stm32f10x_rcc.c **** { + 519 .loc 1 611 0 + 520 @ args = 0, pretend = 0, frame = 0 + 521 @ frame_needed = 0, uses_anonymous_args = 0 + 522 @ link register save eliminated. + 523 .LVL35: + 612:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 613:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 614:stm32lib/src/stm32f10x_rcc.c **** + 615:stm32lib/src/stm32f10x_rcc.c **** *(vu32 *) CSR_LSION_BB = (u32)NewState; + 524 .loc 1 615 0 + 525 0174 014B ldr r3, .L75 + 526 0176 1860 str r0, [r3, #0] + 616:stm32lib/src/stm32f10x_rcc.c **** } + 527 .loc 1 616 0 + 528 0178 7047 bx lr + 529 .L76: + 530 017a 00BF .align 2 + 531 .L75: + 532 017c 80044242 .word 1111622784 + 533 .LFE39: + 535 .align 2 + 536 .global RCC_RTCCLKConfig + 537 .thumb + 538 .thumb_func + 540 RCC_RTCCLKConfig: + 541 .LFB40: + 617:stm32lib/src/stm32f10x_rcc.c **** + 618:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 619:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_RTCCLKConfig + 620:stm32lib/src/stm32f10x_rcc.c **** * Description : Configures the RTC clock (RTCCLK). + 621:stm32lib/src/stm32f10x_rcc.c **** * Once the RTC clock is selected it can’t be changed unless the + 622:stm32lib/src/stm32f10x_rcc.c **** * Backup domain is reset. + 623:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_RTCCLKSource: specifies the RTC clock source. + 624:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be one of the following values: + 625:stm32lib/src/stm32f10x_rcc.c **** * - RCC_RTCCLKSource_LSE: LSE selected as RTC clock + 626:stm32lib/src/stm32f10x_rcc.c **** * - RCC_RTCCLKSource_LSI: LSI selected as RTC clock + 627:stm32lib/src/stm32f10x_rcc.c **** * - RCC_RTCCLKSource_HSE_Div128: HSE clock divided by 128 + 628:stm32lib/src/stm32f10x_rcc.c **** * selected as RTC clock + 629:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 630:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 631:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 632:stm32lib/src/stm32f10x_rcc.c **** void RCC_RTCCLKConfig(u32 RCC_RTCCLKSource) + 633:stm32lib/src/stm32f10x_rcc.c **** { + 542 .loc 1 633 0 + 543 @ args = 0, pretend = 0, frame = 0 + 544 @ frame_needed = 0, uses_anonymous_args = 0 + 545 @ link register save eliminated. + 546 .LVL36: + 634:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 635:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource)); + 636:stm32lib/src/stm32f10x_rcc.c **** + 637:stm32lib/src/stm32f10x_rcc.c **** /* Select the RTC clock source */ + 638:stm32lib/src/stm32f10x_rcc.c **** RCC->BDCR |= RCC_RTCCLKSource; + 547 .loc 1 638 0 + 548 0180 024B ldr r3, .L79 + 549 0182 1A6A ldr r2, [r3, #32] + 550 0184 1043 orrs r0, r0, r2 + 551 .LVL37: + 552 0186 1862 str r0, [r3, #32] + 639:stm32lib/src/stm32f10x_rcc.c **** } + 553 .loc 1 639 0 + 554 0188 7047 bx lr + 555 .L80: + 556 018a 00BF .align 2 + 557 .L79: + 558 018c 00100240 .word 1073876992 + 559 .LFE40: + 561 .align 2 + 562 .global RCC_RTCCLKCmd + 563 .thumb + 564 .thumb_func + 566 RCC_RTCCLKCmd: + 567 .LFB41: + 640:stm32lib/src/stm32f10x_rcc.c **** + 641:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 642:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_RTCCLKCmd + 643:stm32lib/src/stm32f10x_rcc.c **** * Description : Enables or disables the RTC clock. + 644:stm32lib/src/stm32f10x_rcc.c **** * This function must be used only after the RTC clock was + 645:stm32lib/src/stm32f10x_rcc.c **** * selected using the RCC_RTCCLKConfig function. + 646:stm32lib/src/stm32f10x_rcc.c **** * Input : - NewState: new state of the RTC clock. + 647:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be: ENABLE or DISABLE. + 648:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 649:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 650:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 651:stm32lib/src/stm32f10x_rcc.c **** void RCC_RTCCLKCmd(FunctionalState NewState) + 652:stm32lib/src/stm32f10x_rcc.c **** { + 568 .loc 1 652 0 + 569 @ args = 0, pretend = 0, frame = 0 + 570 @ frame_needed = 0, uses_anonymous_args = 0 + 571 @ link register save eliminated. + 572 .LVL38: + 653:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 654:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 655:stm32lib/src/stm32f10x_rcc.c **** + 656:stm32lib/src/stm32f10x_rcc.c **** *(vu32 *) BDCR_RTCEN_BB = (u32)NewState; + 573 .loc 1 656 0 + 574 0190 014B ldr r3, .L83 + 575 0192 1860 str r0, [r3, #0] + 657:stm32lib/src/stm32f10x_rcc.c **** } + 576 .loc 1 657 0 + 577 0194 7047 bx lr + 578 .L84: + 579 0196 00BF .align 2 + 580 .L83: + 581 0198 3C044242 .word 1111622716 + 582 .LFE41: + 584 .align 2 + 585 .global RCC_GetClocksFreq + 586 .thumb + 587 .thumb_func + 589 RCC_GetClocksFreq: + 590 .LFB42: + 658:stm32lib/src/stm32f10x_rcc.c **** + 659:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 660:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_GetClocksFreq + 661:stm32lib/src/stm32f10x_rcc.c **** * Description : Returns the frequencies of different on chip clocks. + 662:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_Clocks: pointer to a RCC_ClocksTypeDef structure which + 663:stm32lib/src/stm32f10x_rcc.c **** * will hold the clocks frequencies. + 664:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 665:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 666:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 667:stm32lib/src/stm32f10x_rcc.c **** void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) + 668:stm32lib/src/stm32f10x_rcc.c **** { + 591 .loc 1 668 0 + 592 @ args = 0, pretend = 0, frame = 0 + 593 @ frame_needed = 0, uses_anonymous_args = 0 + 594 .LVL39: + 669:stm32lib/src/stm32f10x_rcc.c **** u32 tmp = 0, pllmull = 0, pllsource = 0, presc = 0; + 670:stm32lib/src/stm32f10x_rcc.c **** + 671:stm32lib/src/stm32f10x_rcc.c **** /* Get SYSCLK source -------------------------------------------------------*/ + 672:stm32lib/src/stm32f10x_rcc.c **** tmp = RCC->CFGR & CFGR_SWS_Mask; + 595 .loc 1 672 0 + 596 019c 1D49 ldr r1, .L98 + 597 .loc 1 668 0 + 598 019e 10B5 push {r4, lr} + 599 .LCFI0: + 600 .loc 1 672 0 + 601 01a0 4B68 ldr r3, [r1, #4] + 602 .loc 1 668 0 + 603 01a2 0446 mov r4, r0 + 673:stm32lib/src/stm32f10x_rcc.c **** + 674:stm32lib/src/stm32f10x_rcc.c **** switch (tmp) + 604 .loc 1 674 0 + 605 01a4 03F00C03 and r3, r3, #12 + 606 01a8 042B cmp r3, #4 + 607 01aa 12D0 beq .L94 + 608 .LVL40: + 609 01ac 082B cmp r3, #8 + 610 01ae 10D1 bne .L94 + 611 .L89: + 675:stm32lib/src/stm32f10x_rcc.c **** { + 676:stm32lib/src/stm32f10x_rcc.c **** case 0x00: /* HSI used as system clock */ + 677:stm32lib/src/stm32f10x_rcc.c **** RCC_Clocks->SYSCLK_Frequency = HSI_Value; + 678:stm32lib/src/stm32f10x_rcc.c **** break; + 679:stm32lib/src/stm32f10x_rcc.c **** + 680:stm32lib/src/stm32f10x_rcc.c **** case 0x04: /* HSE used as system clock */ + 681:stm32lib/src/stm32f10x_rcc.c **** RCC_Clocks->SYSCLK_Frequency = HSE_Value; + 682:stm32lib/src/stm32f10x_rcc.c **** break; + 683:stm32lib/src/stm32f10x_rcc.c **** + 684:stm32lib/src/stm32f10x_rcc.c **** case 0x08: /* PLL used as system clock */ + 685:stm32lib/src/stm32f10x_rcc.c **** /* Get PLL clock source and multiplication factor ----------------------*/ + 686:stm32lib/src/stm32f10x_rcc.c **** pllmull = RCC->CFGR & CFGR_PLLMull_Mask; + 612 .loc 1 686 0 + 613 01b0 4B68 ldr r3, [r1, #4] + 687:stm32lib/src/stm32f10x_rcc.c **** pllmull = ( pllmull >> 18) + 2; + 614 .loc 1 687 0 + 615 01b2 C3F38343 ubfx r3, r3, #18, #4 + 616 01b6 9A1C adds r2, r3, #2 + 617 .LVL41: + 688:stm32lib/src/stm32f10x_rcc.c **** + 689:stm32lib/src/stm32f10x_rcc.c **** pllsource = RCC->CFGR & CFGR_PLLSRC_Mask; + 618 .loc 1 689 0 + 619 01b8 4B68 ldr r3, [r1, #4] + 690:stm32lib/src/stm32f10x_rcc.c **** + 691:stm32lib/src/stm32f10x_rcc.c **** if (pllsource == 0x00) + 620 .loc 1 691 0 + 621 01ba 13F4803F tst r3, #65536 + 622 01be 03D0 beq .L97 + 623 .L91: + 692:stm32lib/src/stm32f10x_rcc.c **** {/* HSI oscillator clock divided by 2 selected as PLL clock entry */ + 693:stm32lib/src/stm32f10x_rcc.c **** RCC_Clocks->SYSCLK_Frequency = (HSI_Value >> 1) * pllmull; + 694:stm32lib/src/stm32f10x_rcc.c **** } + 695:stm32lib/src/stm32f10x_rcc.c **** else + 696:stm32lib/src/stm32f10x_rcc.c **** {/* HSE selected as PLL clock entry */ + 697:stm32lib/src/stm32f10x_rcc.c **** + 698:stm32lib/src/stm32f10x_rcc.c **** if ((RCC->CFGR & CFGR_PLLXTPRE_Mask) != (u32)RESET) + 624 .loc 1 698 0 + 625 01c0 4B68 ldr r3, [r1, #4] + 626 01c2 13F4003F tst r3, #131072 + 627 01c6 01D0 beq .L92 + 628 .L97: + 699:stm32lib/src/stm32f10x_rcc.c **** {/* HSE oscillator clock divided by 2 */ + 700:stm32lib/src/stm32f10x_rcc.c **** + 701:stm32lib/src/stm32f10x_rcc.c **** RCC_Clocks->SYSCLK_Frequency = (HSE_Value >> 1) * pllmull; + 629 .loc 1 701 0 + 630 01c8 134B ldr r3, .L98+4 + 631 01ca 00E0 b .L96 + 632 .L92: + 702:stm32lib/src/stm32f10x_rcc.c **** } + 703:stm32lib/src/stm32f10x_rcc.c **** else + 704:stm32lib/src/stm32f10x_rcc.c **** { + 705:stm32lib/src/stm32f10x_rcc.c **** RCC_Clocks->SYSCLK_Frequency = HSE_Value * pllmull; + 633 .loc 1 705 0 + 634 01cc 134B ldr r3, .L98+8 + 635 .L96: + 636 01ce 5343 muls r3, r2, r3 + 637 01d0 00E0 b .L95 + 638 .LVL42: + 639 .L94: + 706:stm32lib/src/stm32f10x_rcc.c **** } + 707:stm32lib/src/stm32f10x_rcc.c **** } + 708:stm32lib/src/stm32f10x_rcc.c **** break; + 709:stm32lib/src/stm32f10x_rcc.c **** + 710:stm32lib/src/stm32f10x_rcc.c **** default: + 711:stm32lib/src/stm32f10x_rcc.c **** RCC_Clocks->SYSCLK_Frequency = HSI_Value; + 640 .loc 1 711 0 + 641 01d2 124B ldr r3, .L98+8 + 642 .LVL43: + 643 .L95: + 712:stm32lib/src/stm32f10x_rcc.c **** break; + 713:stm32lib/src/stm32f10x_rcc.c **** } + 714:stm32lib/src/stm32f10x_rcc.c **** + 715:stm32lib/src/stm32f10x_rcc.c **** /* Compute HCLK, PCLK1, PCLK2 and ADCCLK clocks frequencies ----------------*/ + 716:stm32lib/src/stm32f10x_rcc.c **** /* Get HCLK prescaler */ + 717:stm32lib/src/stm32f10x_rcc.c **** tmp = RCC->CFGR & CFGR_HPRE_Set_Mask; + 644 .loc 1 717 0 + 645 01d4 0F48 ldr r0, .L98 + 646 .loc 1 711 0 + 647 01d6 2360 str r3, [r4, #0] + 648 .loc 1 717 0 + 649 01d8 4368 ldr r3, [r0, #4] + 718:stm32lib/src/stm32f10x_rcc.c **** tmp = tmp >> 4; + 719:stm32lib/src/stm32f10x_rcc.c **** presc = APBAHBPrescTable[tmp]; + 720:stm32lib/src/stm32f10x_rcc.c **** + 721:stm32lib/src/stm32f10x_rcc.c **** /* HCLK clock frequency */ + 722:stm32lib/src/stm32f10x_rcc.c **** RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> presc; + 650 .loc 1 722 0 + 651 01da 1149 ldr r1, .L98+12 + 652 01dc C3F30313 ubfx r3, r3, #4, #4 + 653 01e0 CB5C ldrb r3, [r1, r3] @ zero_extendqisi2 + 654 01e2 2268 ldr r2, [r4, #0] + 655 .LVL44: + 656 01e4 DA40 lsrs r2, r2, r3 + 657 01e6 6260 str r2, [r4, #4] + 723:stm32lib/src/stm32f10x_rcc.c **** + 724:stm32lib/src/stm32f10x_rcc.c **** /* Get PCLK1 prescaler */ + 725:stm32lib/src/stm32f10x_rcc.c **** tmp = RCC->CFGR & CFGR_PPRE1_Set_Mask; + 658 .loc 1 725 0 + 659 01e8 4368 ldr r3, [r0, #4] + 726:stm32lib/src/stm32f10x_rcc.c **** tmp = tmp >> 8; + 727:stm32lib/src/stm32f10x_rcc.c **** presc = APBAHBPrescTable[tmp]; + 728:stm32lib/src/stm32f10x_rcc.c **** + 729:stm32lib/src/stm32f10x_rcc.c **** /* PCLK1 clock frequency */ + 730:stm32lib/src/stm32f10x_rcc.c **** RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc; + 660 .loc 1 730 0 + 661 01ea C3F30223 ubfx r3, r3, #8, #3 + 662 01ee CB5C ldrb r3, [r1, r3] @ zero_extendqisi2 + 663 01f0 32FA03F3 lsrs r3, r2, r3 + 664 01f4 A360 str r3, [r4, #8] + 731:stm32lib/src/stm32f10x_rcc.c **** + 732:stm32lib/src/stm32f10x_rcc.c **** /* Get PCLK2 prescaler */ + 733:stm32lib/src/stm32f10x_rcc.c **** tmp = RCC->CFGR & CFGR_PPRE2_Set_Mask; + 665 .loc 1 733 0 + 666 01f6 4368 ldr r3, [r0, #4] + 734:stm32lib/src/stm32f10x_rcc.c **** tmp = tmp >> 11; + 735:stm32lib/src/stm32f10x_rcc.c **** presc = APBAHBPrescTable[tmp]; + 736:stm32lib/src/stm32f10x_rcc.c **** + 737:stm32lib/src/stm32f10x_rcc.c **** /* PCLK2 clock frequency */ + 738:stm32lib/src/stm32f10x_rcc.c **** RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> presc; + 667 .loc 1 738 0 + 668 01f8 C3F3C223 ubfx r3, r3, #11, #3 + 669 01fc CB5C ldrb r3, [r1, r3] @ zero_extendqisi2 + 670 01fe DA40 lsrs r2, r2, r3 + 671 0200 E260 str r2, [r4, #12] + 739:stm32lib/src/stm32f10x_rcc.c **** + 740:stm32lib/src/stm32f10x_rcc.c **** /* Get ADCCLK prescaler */ + 741:stm32lib/src/stm32f10x_rcc.c **** tmp = RCC->CFGR & CFGR_ADCPRE_Set_Mask; + 672 .loc 1 741 0 + 673 0202 4368 ldr r3, [r0, #4] + 742:stm32lib/src/stm32f10x_rcc.c **** tmp = tmp >> 14; + 743:stm32lib/src/stm32f10x_rcc.c **** presc = ADCPrescTable[tmp]; + 744:stm32lib/src/stm32f10x_rcc.c **** + 745:stm32lib/src/stm32f10x_rcc.c **** /* ADCCLK clock frequency */ + 746:stm32lib/src/stm32f10x_rcc.c **** RCC_Clocks->ADCCLK_Frequency = RCC_Clocks->PCLK2_Frequency / presc; + 674 .loc 1 746 0 + 675 0204 C3F38133 ubfx r3, r3, #14, #2 + 676 0208 C918 adds r1, r1, r3 + 677 020a 0B7C ldrb r3, [r1, #16] @ zero_extendqisi2 + 678 020c B2FBF3F2 udiv r2, r2, r3 + 679 0210 2261 str r2, [r4, #16] + 747:stm32lib/src/stm32f10x_rcc.c **** } + 680 .loc 1 747 0 + 681 0212 10BD pop {r4, pc} + 682 .L99: + 683 .align 2 + 684 .L98: + 685 0214 00100240 .word 1073876992 + 686 0218 00093D00 .word 4000000 + 687 021c 00127A00 .word 8000000 + 688 0220 00000000 .word .LANCHOR0 + 689 .LFE42: + 691 .align 2 + 692 .global RCC_AHBPeriphClockCmd + 693 .thumb + 694 .thumb_func + 696 RCC_AHBPeriphClockCmd: + 697 .LFB43: + 748:stm32lib/src/stm32f10x_rcc.c **** + 749:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 750:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_AHBPeriphClockCmd + 751:stm32lib/src/stm32f10x_rcc.c **** * Description : Enables or disables the AHB peripheral clock. + 752:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_AHBPeriph: specifies the AHB peripheral to gates its clock. + 753:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be any combination of the following values: + 754:stm32lib/src/stm32f10x_rcc.c **** * - RCC_AHBPeriph_DMA1 + 755:stm32lib/src/stm32f10x_rcc.c **** * - RCC_AHBPeriph_DMA2 + 756:stm32lib/src/stm32f10x_rcc.c **** * - RCC_AHBPeriph_SRAM + 757:stm32lib/src/stm32f10x_rcc.c **** * - RCC_AHBPeriph_FLITF + 758:stm32lib/src/stm32f10x_rcc.c **** * - RCC_AHBPeriph_CRC + 759:stm32lib/src/stm32f10x_rcc.c **** * - RCC_AHBPeriph_FSMC + 760:stm32lib/src/stm32f10x_rcc.c **** * - RCC_AHBPeriph_SDIO + 761:stm32lib/src/stm32f10x_rcc.c **** * SRAM and FLITF clock can be disabled only during sleep mode. + 762:stm32lib/src/stm32f10x_rcc.c **** * - NewState: new state of the specified peripheral clock. + 763:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be: ENABLE or DISABLE. + 764:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 765:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 766:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 767:stm32lib/src/stm32f10x_rcc.c **** void RCC_AHBPeriphClockCmd(u32 RCC_AHBPeriph, FunctionalState NewState) + 768:stm32lib/src/stm32f10x_rcc.c **** { + 698 .loc 1 768 0 + 699 @ args = 0, pretend = 0, frame = 0 + 700 @ frame_needed = 0, uses_anonymous_args = 0 + 701 @ link register save eliminated. + 702 .LVL45: + 769:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 770:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_AHB_PERIPH(RCC_AHBPeriph)); + 771:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 772:stm32lib/src/stm32f10x_rcc.c **** + 773:stm32lib/src/stm32f10x_rcc.c **** if (NewState != DISABLE) + 703 .loc 1 773 0 + 704 0224 21B1 cbz r1, .L101 + 774:stm32lib/src/stm32f10x_rcc.c **** { + 775:stm32lib/src/stm32f10x_rcc.c **** RCC->AHBENR |= RCC_AHBPeriph; + 705 .loc 1 775 0 + 706 0226 054A ldr r2, .L105 + 707 0228 5369 ldr r3, [r2, #20] + 708 022a 40EA0303 orr r3, r0, r3 + 709 022e 03E0 b .L104 + 710 .L101: + 776:stm32lib/src/stm32f10x_rcc.c **** } + 777:stm32lib/src/stm32f10x_rcc.c **** else + 778:stm32lib/src/stm32f10x_rcc.c **** { + 779:stm32lib/src/stm32f10x_rcc.c **** RCC->AHBENR &= ~RCC_AHBPeriph; + 711 .loc 1 779 0 + 712 0230 024A ldr r2, .L105 + 713 0232 5369 ldr r3, [r2, #20] + 714 0234 23EA0003 bic r3, r3, r0 + 715 .L104: + 716 0238 5361 str r3, [r2, #20] + 780:stm32lib/src/stm32f10x_rcc.c **** } + 781:stm32lib/src/stm32f10x_rcc.c **** } + 717 .loc 1 781 0 + 718 023a 7047 bx lr + 719 .L106: + 720 .align 2 + 721 .L105: + 722 023c 00100240 .word 1073876992 + 723 .LFE43: + 725 .align 2 + 726 .global RCC_APB2PeriphClockCmd + 727 .thumb + 728 .thumb_func + 730 RCC_APB2PeriphClockCmd: + 731 .LFB44: + 782:stm32lib/src/stm32f10x_rcc.c **** + 783:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 784:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_APB2PeriphClockCmd + 785:stm32lib/src/stm32f10x_rcc.c **** * Description : Enables or disables the High Speed APB (APB2) peripheral clock. + 786:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_APB2Periph: specifies the APB2 peripheral to gates its + 787:stm32lib/src/stm32f10x_rcc.c **** * clock. + 788:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be any combination of the following values: + 789:stm32lib/src/stm32f10x_rcc.c **** * - RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB, + 790:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE, + 791:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1, + 792:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1, + 793:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3, + 794:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB2Periph_ALL + 795:stm32lib/src/stm32f10x_rcc.c **** * - NewState: new state of the specified peripheral clock. + 796:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be: ENABLE or DISABLE. + 797:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 798:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 799:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 800:stm32lib/src/stm32f10x_rcc.c **** void RCC_APB2PeriphClockCmd(u32 RCC_APB2Periph, FunctionalState NewState) + 801:stm32lib/src/stm32f10x_rcc.c **** { + 732 .loc 1 801 0 + 733 @ args = 0, pretend = 0, frame = 0 + 734 @ frame_needed = 0, uses_anonymous_args = 0 + 735 @ link register save eliminated. + 736 .LVL46: + 802:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 803:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); + 804:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 805:stm32lib/src/stm32f10x_rcc.c **** + 806:stm32lib/src/stm32f10x_rcc.c **** if (NewState != DISABLE) + 737 .loc 1 806 0 + 738 0240 21B1 cbz r1, .L108 + 807:stm32lib/src/stm32f10x_rcc.c **** { + 808:stm32lib/src/stm32f10x_rcc.c **** RCC->APB2ENR |= RCC_APB2Periph; + 739 .loc 1 808 0 + 740 0242 054A ldr r2, .L112 + 741 0244 9369 ldr r3, [r2, #24] + 742 0246 40EA0303 orr r3, r0, r3 + 743 024a 03E0 b .L111 + 744 .L108: + 809:stm32lib/src/stm32f10x_rcc.c **** } + 810:stm32lib/src/stm32f10x_rcc.c **** else + 811:stm32lib/src/stm32f10x_rcc.c **** { + 812:stm32lib/src/stm32f10x_rcc.c **** RCC->APB2ENR &= ~RCC_APB2Periph; + 745 .loc 1 812 0 + 746 024c 024A ldr r2, .L112 + 747 024e 9369 ldr r3, [r2, #24] + 748 0250 23EA0003 bic r3, r3, r0 + 749 .L111: + 750 0254 9361 str r3, [r2, #24] + 813:stm32lib/src/stm32f10x_rcc.c **** } + 814:stm32lib/src/stm32f10x_rcc.c **** } + 751 .loc 1 814 0 + 752 0256 7047 bx lr + 753 .L113: + 754 .align 2 + 755 .L112: + 756 0258 00100240 .word 1073876992 + 757 .LFE44: + 759 .align 2 + 760 .global RCC_APB1PeriphClockCmd + 761 .thumb + 762 .thumb_func + 764 RCC_APB1PeriphClockCmd: + 765 .LFB45: + 815:stm32lib/src/stm32f10x_rcc.c **** + 816:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 817:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_APB1PeriphClockCmd + 818:stm32lib/src/stm32f10x_rcc.c **** * Description : Enables or disables the Low Speed APB (APB1) peripheral clock. + 819:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_APB1Periph: specifies the APB1 peripheral to gates its + 820:stm32lib/src/stm32f10x_rcc.c **** * clock. + 821:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be any combination of the following values: + 822:stm32lib/src/stm32f10x_rcc.c **** * - RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4, + 823:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7, + 824:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3, + 825:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4, + 826:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2, + 827:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB1Periph_USB, RCC_APB1Periph_CAN, RCC_APB1Periph_BKP, + 828:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_ALL + 829:stm32lib/src/stm32f10x_rcc.c **** * - NewState: new state of the specified peripheral clock. + 830:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be: ENABLE or DISABLE. + 831:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 832:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 833:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 834:stm32lib/src/stm32f10x_rcc.c **** void RCC_APB1PeriphClockCmd(u32 RCC_APB1Periph, FunctionalState NewState) + 835:stm32lib/src/stm32f10x_rcc.c **** { + 766 .loc 1 835 0 + 767 @ args = 0, pretend = 0, frame = 0 + 768 @ frame_needed = 0, uses_anonymous_args = 0 + 769 @ link register save eliminated. + 770 .LVL47: + 836:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 837:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); + 838:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 839:stm32lib/src/stm32f10x_rcc.c **** + 840:stm32lib/src/stm32f10x_rcc.c **** if (NewState != DISABLE) + 771 .loc 1 840 0 + 772 025c 21B1 cbz r1, .L115 + 841:stm32lib/src/stm32f10x_rcc.c **** { + 842:stm32lib/src/stm32f10x_rcc.c **** RCC->APB1ENR |= RCC_APB1Periph; + 773 .loc 1 842 0 + 774 025e 054A ldr r2, .L119 + 775 0260 D369 ldr r3, [r2, #28] + 776 0262 40EA0303 orr r3, r0, r3 + 777 0266 03E0 b .L118 + 778 .L115: + 843:stm32lib/src/stm32f10x_rcc.c **** } + 844:stm32lib/src/stm32f10x_rcc.c **** else + 845:stm32lib/src/stm32f10x_rcc.c **** { + 846:stm32lib/src/stm32f10x_rcc.c **** RCC->APB1ENR &= ~RCC_APB1Periph; + 779 .loc 1 846 0 + 780 0268 024A ldr r2, .L119 + 781 026a D369 ldr r3, [r2, #28] + 782 026c 23EA0003 bic r3, r3, r0 + 783 .L118: + 784 0270 D361 str r3, [r2, #28] + 847:stm32lib/src/stm32f10x_rcc.c **** } + 848:stm32lib/src/stm32f10x_rcc.c **** } + 785 .loc 1 848 0 + 786 0272 7047 bx lr + 787 .L120: + 788 .align 2 + 789 .L119: + 790 0274 00100240 .word 1073876992 + 791 .LFE45: + 793 .align 2 + 794 .global RCC_APB2PeriphResetCmd + 795 .thumb + 796 .thumb_func + 798 RCC_APB2PeriphResetCmd: + 799 .LFB46: + 849:stm32lib/src/stm32f10x_rcc.c **** + 850:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 851:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_APB2PeriphResetCmd + 852:stm32lib/src/stm32f10x_rcc.c **** * Description : Forces or releases High Speed APB (APB2) peripheral reset. + 853:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_APB2Periph: specifies the APB2 peripheral to reset. + 854:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be any combination of the following values: + 855:stm32lib/src/stm32f10x_rcc.c **** * - RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB, + 856:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE, + 857:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1, + 858:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1, + 859:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3, + 860:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB2Periph_ALL + 861:stm32lib/src/stm32f10x_rcc.c **** * - NewState: new state of the specified peripheral reset. + 862:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be: ENABLE or DISABLE. + 863:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 864:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 865:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 866:stm32lib/src/stm32f10x_rcc.c **** void RCC_APB2PeriphResetCmd(u32 RCC_APB2Periph, FunctionalState NewState) + 867:stm32lib/src/stm32f10x_rcc.c **** { + 800 .loc 1 867 0 + 801 @ args = 0, pretend = 0, frame = 0 + 802 @ frame_needed = 0, uses_anonymous_args = 0 + 803 @ link register save eliminated. + 804 .LVL48: + 868:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 869:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); + 870:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 871:stm32lib/src/stm32f10x_rcc.c **** + 872:stm32lib/src/stm32f10x_rcc.c **** if (NewState != DISABLE) + 805 .loc 1 872 0 + 806 0278 21B1 cbz r1, .L122 + 873:stm32lib/src/stm32f10x_rcc.c **** { + 874:stm32lib/src/stm32f10x_rcc.c **** RCC->APB2RSTR |= RCC_APB2Periph; + 807 .loc 1 874 0 + 808 027a 054A ldr r2, .L126 + 809 027c D368 ldr r3, [r2, #12] + 810 027e 40EA0303 orr r3, r0, r3 + 811 0282 03E0 b .L125 + 812 .L122: + 875:stm32lib/src/stm32f10x_rcc.c **** } + 876:stm32lib/src/stm32f10x_rcc.c **** else + 877:stm32lib/src/stm32f10x_rcc.c **** { + 878:stm32lib/src/stm32f10x_rcc.c **** RCC->APB2RSTR &= ~RCC_APB2Periph; + 813 .loc 1 878 0 + 814 0284 024A ldr r2, .L126 + 815 0286 D368 ldr r3, [r2, #12] + 816 0288 23EA0003 bic r3, r3, r0 + 817 .L125: + 818 028c D360 str r3, [r2, #12] + 879:stm32lib/src/stm32f10x_rcc.c **** } + 880:stm32lib/src/stm32f10x_rcc.c **** } + 819 .loc 1 880 0 + 820 028e 7047 bx lr + 821 .L127: + 822 .align 2 + 823 .L126: + 824 0290 00100240 .word 1073876992 + 825 .LFE46: + 827 .align 2 + 828 .global RCC_APB1PeriphResetCmd + 829 .thumb + 830 .thumb_func + 832 RCC_APB1PeriphResetCmd: + 833 .LFB47: + 881:stm32lib/src/stm32f10x_rcc.c **** + 882:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 883:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_APB1PeriphResetCmd + 884:stm32lib/src/stm32f10x_rcc.c **** * Description : Forces or releases Low Speed APB (APB1) peripheral reset. + 885:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_APB1Periph: specifies the APB1 peripheral to reset. + 886:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be any combination of the following values: + 887:stm32lib/src/stm32f10x_rcc.c **** * - RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4, + 888:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7, + 889:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3, + 890:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4, + 891:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2, + 892:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB1Periph_USB, RCC_APB1Periph_CAN, RCC_APB1Periph_BKP, + 893:stm32lib/src/stm32f10x_rcc.c **** * RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_ALL + 894:stm32lib/src/stm32f10x_rcc.c **** * - NewState: new state of the specified peripheral clock. + 895:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be: ENABLE or DISABLE. + 896:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 897:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 898:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 899:stm32lib/src/stm32f10x_rcc.c **** void RCC_APB1PeriphResetCmd(u32 RCC_APB1Periph, FunctionalState NewState) + 900:stm32lib/src/stm32f10x_rcc.c **** { + 834 .loc 1 900 0 + 835 @ args = 0, pretend = 0, frame = 0 + 836 @ frame_needed = 0, uses_anonymous_args = 0 + 837 @ link register save eliminated. + 838 .LVL49: + 901:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 902:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); + 903:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 904:stm32lib/src/stm32f10x_rcc.c **** + 905:stm32lib/src/stm32f10x_rcc.c **** if (NewState != DISABLE) + 839 .loc 1 905 0 + 840 0294 21B1 cbz r1, .L129 + 906:stm32lib/src/stm32f10x_rcc.c **** { + 907:stm32lib/src/stm32f10x_rcc.c **** RCC->APB1RSTR |= RCC_APB1Periph; + 841 .loc 1 907 0 + 842 0296 054A ldr r2, .L133 + 843 0298 1369 ldr r3, [r2, #16] + 844 029a 40EA0303 orr r3, r0, r3 + 845 029e 03E0 b .L132 + 846 .L129: + 908:stm32lib/src/stm32f10x_rcc.c **** } + 909:stm32lib/src/stm32f10x_rcc.c **** else + 910:stm32lib/src/stm32f10x_rcc.c **** { + 911:stm32lib/src/stm32f10x_rcc.c **** RCC->APB1RSTR &= ~RCC_APB1Periph; + 847 .loc 1 911 0 + 848 02a0 024A ldr r2, .L133 + 849 02a2 1369 ldr r3, [r2, #16] + 850 02a4 23EA0003 bic r3, r3, r0 + 851 .L132: + 852 02a8 1361 str r3, [r2, #16] + 912:stm32lib/src/stm32f10x_rcc.c **** } + 913:stm32lib/src/stm32f10x_rcc.c **** } + 853 .loc 1 913 0 + 854 02aa 7047 bx lr + 855 .L134: + 856 .align 2 + 857 .L133: + 858 02ac 00100240 .word 1073876992 + 859 .LFE47: + 861 .align 2 + 862 .global RCC_BackupResetCmd + 863 .thumb + 864 .thumb_func + 866 RCC_BackupResetCmd: + 867 .LFB48: + 914:stm32lib/src/stm32f10x_rcc.c **** + 915:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 916:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_BackupResetCmd + 917:stm32lib/src/stm32f10x_rcc.c **** * Description : Forces or releases the Backup domain reset. + 918:stm32lib/src/stm32f10x_rcc.c **** * Input : - NewState: new state of the Backup domain reset. + 919:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be: ENABLE or DISABLE. + 920:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 921:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 922:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 923:stm32lib/src/stm32f10x_rcc.c **** void RCC_BackupResetCmd(FunctionalState NewState) + 924:stm32lib/src/stm32f10x_rcc.c **** { + 868 .loc 1 924 0 + 869 @ args = 0, pretend = 0, frame = 0 + 870 @ frame_needed = 0, uses_anonymous_args = 0 + 871 @ link register save eliminated. + 872 .LVL50: + 925:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 926:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 927:stm32lib/src/stm32f10x_rcc.c **** + 928:stm32lib/src/stm32f10x_rcc.c **** *(vu32 *) BDCR_BDRST_BB = (u32)NewState; + 873 .loc 1 928 0 + 874 02b0 014B ldr r3, .L137 + 875 02b2 1860 str r0, [r3, #0] + 929:stm32lib/src/stm32f10x_rcc.c **** } + 876 .loc 1 929 0 + 877 02b4 7047 bx lr + 878 .L138: + 879 02b6 00BF .align 2 + 880 .L137: + 881 02b8 40044242 .word 1111622720 + 882 .LFE48: + 884 .align 2 + 885 .global RCC_ClockSecuritySystemCmd + 886 .thumb + 887 .thumb_func + 889 RCC_ClockSecuritySystemCmd: + 890 .LFB49: + 930:stm32lib/src/stm32f10x_rcc.c **** + 931:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 932:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_ClockSecuritySystemCmd + 933:stm32lib/src/stm32f10x_rcc.c **** * Description : Enables or disables the Clock Security System. + 934:stm32lib/src/stm32f10x_rcc.c **** * Input : - NewState: new state of the Clock Security System.. + 935:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be: ENABLE or DISABLE. + 936:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 937:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 938:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 939:stm32lib/src/stm32f10x_rcc.c **** void RCC_ClockSecuritySystemCmd(FunctionalState NewState) + 940:stm32lib/src/stm32f10x_rcc.c **** { + 891 .loc 1 940 0 + 892 @ args = 0, pretend = 0, frame = 0 + 893 @ frame_needed = 0, uses_anonymous_args = 0 + 894 @ link register save eliminated. + 895 .LVL51: + 941:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 942:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 943:stm32lib/src/stm32f10x_rcc.c **** + 944:stm32lib/src/stm32f10x_rcc.c **** *(vu32 *) CR_CSSON_BB = (u32)NewState; + 896 .loc 1 944 0 + 897 02bc 014B ldr r3, .L141 + 898 02be 1860 str r0, [r3, #0] + 945:stm32lib/src/stm32f10x_rcc.c **** } + 899 .loc 1 945 0 + 900 02c0 7047 bx lr + 901 .L142: + 902 02c2 00BF .align 2 + 903 .L141: + 904 02c4 4C004242 .word 1111621708 + 905 .LFE49: + 907 .align 2 + 908 .global RCC_MCOConfig + 909 .thumb + 910 .thumb_func + 912 RCC_MCOConfig: + 913 .LFB50: + 946:stm32lib/src/stm32f10x_rcc.c **** + 947:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 948:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_MCOConfig + 949:stm32lib/src/stm32f10x_rcc.c **** * Description : Selects the clock source to output on MCO pin. + 950:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_MCO: specifies the clock source to output. + 951:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be one of the following values: + 952:stm32lib/src/stm32f10x_rcc.c **** * - RCC_MCO_NoClock: No clock selected + 953:stm32lib/src/stm32f10x_rcc.c **** * - RCC_MCO_SYSCLK: System clock selected + 954:stm32lib/src/stm32f10x_rcc.c **** * - RCC_MCO_HSI: HSI oscillator clock selected + 955:stm32lib/src/stm32f10x_rcc.c **** * - RCC_MCO_HSE: HSE oscillator clock selected + 956:stm32lib/src/stm32f10x_rcc.c **** * - RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected + 957:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 958:stm32lib/src/stm32f10x_rcc.c **** * Return : None + 959:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 960:stm32lib/src/stm32f10x_rcc.c **** void RCC_MCOConfig(u8 RCC_MCO) + 961:stm32lib/src/stm32f10x_rcc.c **** { + 914 .loc 1 961 0 + 915 @ args = 0, pretend = 0, frame = 0 + 916 @ frame_needed = 0, uses_anonymous_args = 0 + 917 @ link register save eliminated. + 918 .LVL52: + 962:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 963:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_MCO(RCC_MCO)); + 964:stm32lib/src/stm32f10x_rcc.c **** + 965:stm32lib/src/stm32f10x_rcc.c **** /* Perform Byte access to MCO[2:0] bits to select the MCO source */ + 966:stm32lib/src/stm32f10x_rcc.c **** *(vu8 *) CFGR_BYTE4_ADDRESS = RCC_MCO; + 919 .loc 1 966 0 + 920 02c8 014B ldr r3, .L145 + 921 02ca 1870 strb r0, [r3, #0] + 967:stm32lib/src/stm32f10x_rcc.c **** } + 922 .loc 1 967 0 + 923 02cc 7047 bx lr + 924 .L146: + 925 02ce 00BF .align 2 + 926 .L145: + 927 02d0 07100240 .word 1073876999 + 928 .LFE50: + 930 .align 2 + 931 .global RCC_GetFlagStatus + 932 .thumb + 933 .thumb_func + 935 RCC_GetFlagStatus: + 936 .LFB51: + 968:stm32lib/src/stm32f10x_rcc.c **** + 969:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* + 970:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_GetFlagStatus + 971:stm32lib/src/stm32f10x_rcc.c **** * Description : Checks whether the specified RCC flag is set or not. + 972:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_FLAG: specifies the flag to check. + 973:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be one of the following values: + 974:stm32lib/src/stm32f10x_rcc.c **** * - RCC_FLAG_HSIRDY: HSI oscillator clock ready + 975:stm32lib/src/stm32f10x_rcc.c **** * - RCC_FLAG_HSERDY: HSE oscillator clock ready + 976:stm32lib/src/stm32f10x_rcc.c **** * - RCC_FLAG_PLLRDY: PLL clock ready + 977:stm32lib/src/stm32f10x_rcc.c **** * - RCC_FLAG_LSERDY: LSE oscillator clock ready + 978:stm32lib/src/stm32f10x_rcc.c **** * - RCC_FLAG_LSIRDY: LSI oscillator clock ready + 979:stm32lib/src/stm32f10x_rcc.c **** * - RCC_FLAG_PINRST: Pin reset + 980:stm32lib/src/stm32f10x_rcc.c **** * - RCC_FLAG_PORRST: POR/PDR reset + 981:stm32lib/src/stm32f10x_rcc.c **** * - RCC_FLAG_SFTRST: Software reset + 982:stm32lib/src/stm32f10x_rcc.c **** * - RCC_FLAG_IWDGRST: Independent Watchdog reset + 983:stm32lib/src/stm32f10x_rcc.c **** * - RCC_FLAG_WWDGRST: Window Watchdog reset + 984:stm32lib/src/stm32f10x_rcc.c **** * - RCC_FLAG_LPWRRST: Low Power reset + 985:stm32lib/src/stm32f10x_rcc.c **** * Output : None + 986:stm32lib/src/stm32f10x_rcc.c **** * Return : The new state of RCC_FLAG (SET or RESET). + 987:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ + 988:stm32lib/src/stm32f10x_rcc.c **** FlagStatus RCC_GetFlagStatus(u8 RCC_FLAG) + 989:stm32lib/src/stm32f10x_rcc.c **** { + 937 .loc 1 989 0 + 938 @ args = 0, pretend = 0, frame = 0 + 939 @ frame_needed = 0, uses_anonymous_args = 0 + 940 @ link register save eliminated. + 941 .LVL53: + 990:stm32lib/src/stm32f10x_rcc.c **** u32 tmp = 0; + 991:stm32lib/src/stm32f10x_rcc.c **** u32 statusreg = 0; + 992:stm32lib/src/stm32f10x_rcc.c **** FlagStatus bitstatus = RESET; + 993:stm32lib/src/stm32f10x_rcc.c **** + 994:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ + 995:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_FLAG(RCC_FLAG)); + 996:stm32lib/src/stm32f10x_rcc.c **** + 997:stm32lib/src/stm32f10x_rcc.c **** /* Get the RCC register index */ + 998:stm32lib/src/stm32f10x_rcc.c **** tmp = RCC_FLAG >> 5; + 942 .loc 1 998 0 + 943 02d4 4309 lsrs r3, r0, #5 + 944 .LVL54: + 999:stm32lib/src/stm32f10x_rcc.c **** +1000:stm32lib/src/stm32f10x_rcc.c **** if (tmp == 1) /* The flag to check is in CR register */ + 945 .loc 1 1000 0 + 946 02d6 012B cmp r3, #1 + 947 02d8 02D1 bne .L148 +1001:stm32lib/src/stm32f10x_rcc.c **** { +1002:stm32lib/src/stm32f10x_rcc.c **** statusreg = RCC->CR; + 948 .loc 1 1002 0 + 949 02da 084B ldr r3, .L152 + 950 .LVL55: + 951 02dc 1B68 ldr r3, [r3, #0] + 952 .LVL56: + 953 02de 05E0 b .L149 + 954 .LVL57: + 955 .L148: +1003:stm32lib/src/stm32f10x_rcc.c **** } +1004:stm32lib/src/stm32f10x_rcc.c **** else if (tmp == 2) /* The flag to check is in BDCR register */ + 956 .loc 1 1004 0 + 957 02e0 022B cmp r3, #2 +1005:stm32lib/src/stm32f10x_rcc.c **** { +1006:stm32lib/src/stm32f10x_rcc.c **** statusreg = RCC->BDCR; + 958 .loc 1 1006 0 + 959 02e2 0BBF itete eq + 960 02e4 054B ldreq r3, .L152 + 961 .LVL58: +1007:stm32lib/src/stm32f10x_rcc.c **** } +1008:stm32lib/src/stm32f10x_rcc.c **** else /* The flag to check is in CSR register */ +1009:stm32lib/src/stm32f10x_rcc.c **** { +1010:stm32lib/src/stm32f10x_rcc.c **** statusreg = RCC->CSR; + 962 .loc 1 1010 0 + 963 02e6 054B ldrne r3, .L152 + 964 .loc 1 1006 0 + 965 02e8 1B6A ldreq r3, [r3, #32] + 966 .LVL59: + 967 .loc 1 1010 0 + 968 02ea 5B6A ldrne r3, [r3, #36] + 969 .LVL60: + 970 .L149: + 971 02ec 00F01F00 and r0, r0, #31 + 972 .LVL61: + 973 02f0 33FA00F0 lsrs r0, r3, r0 +1011:stm32lib/src/stm32f10x_rcc.c **** } +1012:stm32lib/src/stm32f10x_rcc.c **** +1013:stm32lib/src/stm32f10x_rcc.c **** /* Get the flag position */ +1014:stm32lib/src/stm32f10x_rcc.c **** tmp = RCC_FLAG & FLAG_Mask; +1015:stm32lib/src/stm32f10x_rcc.c **** +1016:stm32lib/src/stm32f10x_rcc.c **** if ((statusreg & ((u32)1 << tmp)) != (u32)RESET) +1017:stm32lib/src/stm32f10x_rcc.c **** { +1018:stm32lib/src/stm32f10x_rcc.c **** bitstatus = SET; +1019:stm32lib/src/stm32f10x_rcc.c **** } +1020:stm32lib/src/stm32f10x_rcc.c **** else +1021:stm32lib/src/stm32f10x_rcc.c **** { +1022:stm32lib/src/stm32f10x_rcc.c **** bitstatus = RESET; +1023:stm32lib/src/stm32f10x_rcc.c **** } +1024:stm32lib/src/stm32f10x_rcc.c **** +1025:stm32lib/src/stm32f10x_rcc.c **** /* Return the flag status */ +1026:stm32lib/src/stm32f10x_rcc.c **** return bitstatus; +1027:stm32lib/src/stm32f10x_rcc.c **** } + 974 .loc 1 1027 0 + 975 02f4 00F00100 and r0, r0, #1 + 976 02f8 7047 bx lr + 977 .L153: + 978 02fa 00BF .align 2 + 979 .L152: + 980 02fc 00100240 .word 1073876992 + 981 .LFE51: + 983 .align 2 + 984 .global RCC_WaitForHSEStartUp + 985 .thumb + 986 .thumb_func + 988 RCC_WaitForHSEStartUp: + 989 .LFB25: + 990 .loc 1 200 0 + 991 @ args = 0, pretend = 0, frame = 0 + 992 @ frame_needed = 0, uses_anonymous_args = 0 + 993 0300 10B5 push {r4, lr} + 994 .LCFI1: + 995 .L156: + 996 .loc 1 206 0 + 997 0302 3120 movs r0, #49 + 998 0304 FFF7FEFF bl RCC_GetFlagStatus + 999 0308 094A ldr r2, .L158 + 1000 030a 1070 strb r0, [r2, #0] + 1001 .loc 1 207 0 + 1002 030c 5368 ldr r3, [r2, #4] + 1003 030e 0133 adds r3, r3, #1 + 1004 0310 5360 str r3, [r2, #4] + 1005 .loc 1 208 0 + 1006 0312 1378 ldrb r3, [r2, #0] @ zero_extendqisi2 + 1007 0314 23B9 cbnz r3, .L155 + 1008 0316 5268 ldr r2, [r2, #4] + 1009 0318 40F2FF13 movw r3, #511 + 1010 031c 9A42 cmp r2, r3 + 1011 031e F0D1 bne .L156 + 1012 .L155: + 1013 .loc 1 211 0 + 1014 0320 3120 movs r0, #49 + 1015 0322 FFF7FEFF bl RCC_GetFlagStatus + 1016 .loc 1 221 0 + 1017 0326 0038 subs r0, r0, #0 + 1018 0328 18BF it ne + 1019 032a 0120 movne r0, #1 + 1020 032c 10BD pop {r4, pc} + 1021 .L159: + 1022 032e 00BF .align 2 + 1023 .L158: + 1024 0330 00000000 .word .LANCHOR1 + 1025 .LFE25: + 1027 .align 2 + 1028 .global RCC_ClearFlag + 1029 .thumb + 1030 .thumb_func + 1032 RCC_ClearFlag: + 1033 .LFB52: +1028:stm32lib/src/stm32f10x_rcc.c **** +1029:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* +1030:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_ClearFlag +1031:stm32lib/src/stm32f10x_rcc.c **** * Description : Clears the RCC reset flags. +1032:stm32lib/src/stm32f10x_rcc.c **** * The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST, +1033:stm32lib/src/stm32f10x_rcc.c **** * RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, +1034:stm32lib/src/stm32f10x_rcc.c **** * RCC_FLAG_LPWRRST +1035:stm32lib/src/stm32f10x_rcc.c **** * Input : None +1036:stm32lib/src/stm32f10x_rcc.c **** * Output : None +1037:stm32lib/src/stm32f10x_rcc.c **** * Return : None +1038:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ +1039:stm32lib/src/stm32f10x_rcc.c **** void RCC_ClearFlag(void) +1040:stm32lib/src/stm32f10x_rcc.c **** { + 1034 .loc 1 1040 0 + 1035 @ args = 0, pretend = 0, frame = 0 + 1036 @ frame_needed = 0, uses_anonymous_args = 0 + 1037 @ link register save eliminated. +1041:stm32lib/src/stm32f10x_rcc.c **** /* Set RMVF bit to clear the reset flags */ +1042:stm32lib/src/stm32f10x_rcc.c **** RCC->CSR |= CSR_RMVF_Set; + 1038 .loc 1 1042 0 + 1039 0334 024A ldr r2, .L162 + 1040 0336 536A ldr r3, [r2, #36] + 1041 0338 43F08073 orr r3, r3, #16777216 + 1042 033c 5362 str r3, [r2, #36] +1043:stm32lib/src/stm32f10x_rcc.c **** } + 1043 .loc 1 1043 0 + 1044 033e 7047 bx lr + 1045 .L163: + 1046 .align 2 + 1047 .L162: + 1048 0340 00100240 .word 1073876992 + 1049 .LFE52: + 1051 .align 2 + 1052 .global RCC_GetITStatus + 1053 .thumb + 1054 .thumb_func + 1056 RCC_GetITStatus: + 1057 .LFB53: +1044:stm32lib/src/stm32f10x_rcc.c **** +1045:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* +1046:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_GetITStatus +1047:stm32lib/src/stm32f10x_rcc.c **** * Description : Checks whether the specified RCC interrupt has occurred or not. +1048:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_IT: specifies the RCC interrupt source to check. +1049:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be one of the following values: +1050:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_LSIRDY: LSI ready interrupt +1051:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_LSERDY: LSE ready interrupt +1052:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_HSIRDY: HSI ready interrupt +1053:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_HSERDY: HSE ready interrupt +1054:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_PLLRDY: PLL ready interrupt +1055:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_CSS: Clock Security System interrupt +1056:stm32lib/src/stm32f10x_rcc.c **** * Output : None +1057:stm32lib/src/stm32f10x_rcc.c **** * Return : The new state of RCC_IT (SET or RESET). +1058:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ +1059:stm32lib/src/stm32f10x_rcc.c **** ITStatus RCC_GetITStatus(u8 RCC_IT) +1060:stm32lib/src/stm32f10x_rcc.c **** { + 1058 .loc 1 1060 0 + 1059 @ args = 0, pretend = 0, frame = 0 + 1060 @ frame_needed = 0, uses_anonymous_args = 0 + 1061 @ link register save eliminated. + 1062 .LVL62: +1061:stm32lib/src/stm32f10x_rcc.c **** ITStatus bitstatus = RESET; +1062:stm32lib/src/stm32f10x_rcc.c **** +1063:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ +1064:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_GET_IT(RCC_IT)); +1065:stm32lib/src/stm32f10x_rcc.c **** +1066:stm32lib/src/stm32f10x_rcc.c **** /* Check the status of the specified RCC interrupt */ +1067:stm32lib/src/stm32f10x_rcc.c **** if ((RCC->CIR & RCC_IT) != (u32)RESET) + 1063 .loc 1 1067 0 + 1064 0344 034B ldr r3, .L166 + 1065 0346 9B68 ldr r3, [r3, #8] + 1066 0348 1842 tst r0, r3 +1068:stm32lib/src/stm32f10x_rcc.c **** { +1069:stm32lib/src/stm32f10x_rcc.c **** bitstatus = SET; +1070:stm32lib/src/stm32f10x_rcc.c **** } +1071:stm32lib/src/stm32f10x_rcc.c **** else +1072:stm32lib/src/stm32f10x_rcc.c **** { +1073:stm32lib/src/stm32f10x_rcc.c **** bitstatus = RESET; +1074:stm32lib/src/stm32f10x_rcc.c **** } +1075:stm32lib/src/stm32f10x_rcc.c **** +1076:stm32lib/src/stm32f10x_rcc.c **** /* Return the RCC_IT status */ +1077:stm32lib/src/stm32f10x_rcc.c **** return bitstatus; +1078:stm32lib/src/stm32f10x_rcc.c **** } + 1067 .loc 1 1078 0 + 1068 034a 0CBF ite eq + 1069 034c 0020 moveq r0, #0 + 1070 034e 0120 movne r0, #1 + 1071 .LVL63: + 1072 0350 7047 bx lr + 1073 .L167: + 1074 0352 00BF .align 2 + 1075 .L166: + 1076 0354 00100240 .word 1073876992 + 1077 .LFE53: + 1079 .align 2 + 1080 .global RCC_ClearITPendingBit + 1081 .thumb + 1082 .thumb_func + 1084 RCC_ClearITPendingBit: + 1085 .LFB54: +1079:stm32lib/src/stm32f10x_rcc.c **** +1080:stm32lib/src/stm32f10x_rcc.c **** /******************************************************************************* +1081:stm32lib/src/stm32f10x_rcc.c **** * Function Name : RCC_ClearITPendingBit +1082:stm32lib/src/stm32f10x_rcc.c **** * Description : Clears the RCC’s interrupt pending bits. +1083:stm32lib/src/stm32f10x_rcc.c **** * Input : - RCC_IT: specifies the interrupt pending bit to clear. +1084:stm32lib/src/stm32f10x_rcc.c **** * This parameter can be any combination of the following values: +1085:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_LSIRDY: LSI ready interrupt +1086:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_LSERDY: LSE ready interrupt +1087:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_HSIRDY: HSI ready interrupt +1088:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_HSERDY: HSE ready interrupt +1089:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_PLLRDY: PLL ready interrupt +1090:stm32lib/src/stm32f10x_rcc.c **** * - RCC_IT_CSS: Clock Security System interrupt +1091:stm32lib/src/stm32f10x_rcc.c **** * Output : None +1092:stm32lib/src/stm32f10x_rcc.c **** * Return : None +1093:stm32lib/src/stm32f10x_rcc.c **** *******************************************************************************/ +1094:stm32lib/src/stm32f10x_rcc.c **** void RCC_ClearITPendingBit(u8 RCC_IT) +1095:stm32lib/src/stm32f10x_rcc.c **** { + 1086 .loc 1 1095 0 + 1087 @ args = 0, pretend = 0, frame = 0 + 1088 @ frame_needed = 0, uses_anonymous_args = 0 + 1089 @ link register save eliminated. + 1090 .LVL64: +1096:stm32lib/src/stm32f10x_rcc.c **** /* Check the parameters */ +1097:stm32lib/src/stm32f10x_rcc.c **** assert_param(IS_RCC_CLEAR_IT(RCC_IT)); +1098:stm32lib/src/stm32f10x_rcc.c **** +1099:stm32lib/src/stm32f10x_rcc.c **** /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt +1100:stm32lib/src/stm32f10x_rcc.c **** pending bits */ +1101:stm32lib/src/stm32f10x_rcc.c **** *(vu8 *) CIR_BYTE3_ADDRESS = RCC_IT; + 1091 .loc 1 1101 0 + 1092 0358 014B ldr r3, .L170 + 1093 035a 1870 strb r0, [r3, #0] +1102:stm32lib/src/stm32f10x_rcc.c **** } + 1094 .loc 1 1102 0 + 1095 035c 7047 bx lr + 1096 .L171: + 1097 035e 00BF .align 2 + 1098 .L170: + 1099 0360 0A100240 .word 1073877002 + 1100 .LFE54: + 1102 .section .rodata + 1103 .set .LANCHOR0,. + 0 + 1106 APBAHBPrescTable: + 1107 0000 00 .byte 0 + 1108 0001 00 .byte 0 + 1109 0002 00 .byte 0 + 1110 0003 00 .byte 0 + 1111 0004 01 .byte 1 + 1112 0005 02 .byte 2 + 1113 0006 03 .byte 3 + 1114 0007 04 .byte 4 + 1115 0008 01 .byte 1 + 1116 0009 02 .byte 2 + 1117 000a 03 .byte 3 + 1118 000b 04 .byte 4 + 1119 000c 06 .byte 6 + 1120 000d 07 .byte 7 + 1121 000e 08 .byte 8 + 1122 000f 09 .byte 9 + 1125 ADCPrescTable: + 1126 0010 02 .byte 2 + 1127 0011 04 .byte 4 + 1128 0012 06 .byte 6 + 1129 0013 08 .byte 8 + 1130 .bss + 1131 .align 2 + 1132 .set .LANCHOR1,. + 0 + 1135 HSEStatus: + 1136 0000 00 .space 1 + 1137 0001 000000 .space 3 + 1140 StartUpCounter: + 1141 0004 00000000 .space 4 + 1430 .Letext0: +DEFINED SYMBOLS + *ABS*:00000000 stm32f10x_rcc.c + /tmp/cck1KuUa.s:22 .text:00000000 $t + /tmp/cck1KuUa.s:27 .text:00000000 RCC_DeInit + /tmp/cck1KuUa.s:65 .text:00000038 $d + /tmp/cck1KuUa.s:69 .text:00000040 $t + /tmp/cck1KuUa.s:74 .text:00000040 RCC_HSEConfig + /tmp/cck1KuUa.s:115 .text:00000074 $d + /tmp/cck1KuUa.s:118 .text:00000078 $t + /tmp/cck1KuUa.s:123 .text:00000078 RCC_AdjustHSICalibrationValue + /tmp/cck1KuUa.s:147 .text:00000088 $d + /tmp/cck1KuUa.s:150 .text:0000008c $t + /tmp/cck1KuUa.s:155 .text:0000008c RCC_HSICmd + /tmp/cck1KuUa.s:170 .text:00000094 $d + /tmp/cck1KuUa.s:173 .text:00000098 $t + /tmp/cck1KuUa.s:178 .text:00000098 RCC_PLLConfig + /tmp/cck1KuUa.s:203 .text:000000a8 $d + /tmp/cck1KuUa.s:206 .text:000000ac $t + /tmp/cck1KuUa.s:211 .text:000000ac RCC_PLLCmd + /tmp/cck1KuUa.s:226 .text:000000b4 $d + /tmp/cck1KuUa.s:229 .text:000000b8 $t + /tmp/cck1KuUa.s:234 .text:000000b8 RCC_SYSCLKConfig + /tmp/cck1KuUa.s:258 .text:000000c8 $d + /tmp/cck1KuUa.s:261 .text:000000cc $t + /tmp/cck1KuUa.s:266 .text:000000cc RCC_GetSYSCLKSource + /tmp/cck1KuUa.s:281 .text:000000d8 $d + /tmp/cck1KuUa.s:284 .text:000000dc $t + /tmp/cck1KuUa.s:289 .text:000000dc RCC_HCLKConfig + /tmp/cck1KuUa.s:313 .text:000000ec $d + /tmp/cck1KuUa.s:316 .text:000000f0 $t + /tmp/cck1KuUa.s:321 .text:000000f0 RCC_PCLK1Config + /tmp/cck1KuUa.s:345 .text:00000100 $d + /tmp/cck1KuUa.s:348 .text:00000104 $t + /tmp/cck1KuUa.s:353 .text:00000104 RCC_PCLK2Config + /tmp/cck1KuUa.s:377 .text:00000114 $d + /tmp/cck1KuUa.s:380 .text:00000118 $t + /tmp/cck1KuUa.s:385 .text:00000118 RCC_ITConfig + /tmp/cck1KuUa.s:411 .text:00000130 $d + /tmp/cck1KuUa.s:414 .text:00000134 $t + /tmp/cck1KuUa.s:419 .text:00000134 RCC_USBCLKConfig + /tmp/cck1KuUa.s:434 .text:0000013c $d + /tmp/cck1KuUa.s:437 .text:00000140 $t + /tmp/cck1KuUa.s:442 .text:00000140 RCC_ADCCLKConfig + /tmp/cck1KuUa.s:466 .text:00000150 $d + /tmp/cck1KuUa.s:469 .text:00000154 $t + /tmp/cck1KuUa.s:474 .text:00000154 RCC_LSEConfig + /tmp/cck1KuUa.s:509 .text:00000170 $d + /tmp/cck1KuUa.s:512 .text:00000174 $t + /tmp/cck1KuUa.s:517 .text:00000174 RCC_LSICmd + /tmp/cck1KuUa.s:532 .text:0000017c $d + /tmp/cck1KuUa.s:535 .text:00000180 $t + /tmp/cck1KuUa.s:540 .text:00000180 RCC_RTCCLKConfig + /tmp/cck1KuUa.s:558 .text:0000018c $d + /tmp/cck1KuUa.s:561 .text:00000190 $t + /tmp/cck1KuUa.s:566 .text:00000190 RCC_RTCCLKCmd + /tmp/cck1KuUa.s:581 .text:00000198 $d + /tmp/cck1KuUa.s:584 .text:0000019c $t + /tmp/cck1KuUa.s:589 .text:0000019c RCC_GetClocksFreq + /tmp/cck1KuUa.s:685 .text:00000214 $d + /tmp/cck1KuUa.s:691 .text:00000224 $t + /tmp/cck1KuUa.s:696 .text:00000224 RCC_AHBPeriphClockCmd + /tmp/cck1KuUa.s:722 .text:0000023c $d + /tmp/cck1KuUa.s:725 .text:00000240 $t + /tmp/cck1KuUa.s:730 .text:00000240 RCC_APB2PeriphClockCmd + /tmp/cck1KuUa.s:756 .text:00000258 $d + /tmp/cck1KuUa.s:759 .text:0000025c $t + /tmp/cck1KuUa.s:764 .text:0000025c RCC_APB1PeriphClockCmd + /tmp/cck1KuUa.s:790 .text:00000274 $d + /tmp/cck1KuUa.s:793 .text:00000278 $t + /tmp/cck1KuUa.s:798 .text:00000278 RCC_APB2PeriphResetCmd + /tmp/cck1KuUa.s:824 .text:00000290 $d + /tmp/cck1KuUa.s:827 .text:00000294 $t + /tmp/cck1KuUa.s:832 .text:00000294 RCC_APB1PeriphResetCmd + /tmp/cck1KuUa.s:858 .text:000002ac $d + /tmp/cck1KuUa.s:861 .text:000002b0 $t + /tmp/cck1KuUa.s:866 .text:000002b0 RCC_BackupResetCmd + /tmp/cck1KuUa.s:881 .text:000002b8 $d + /tmp/cck1KuUa.s:884 .text:000002bc $t + /tmp/cck1KuUa.s:889 .text:000002bc RCC_ClockSecuritySystemCmd + /tmp/cck1KuUa.s:904 .text:000002c4 $d + /tmp/cck1KuUa.s:907 .text:000002c8 $t + /tmp/cck1KuUa.s:912 .text:000002c8 RCC_MCOConfig + /tmp/cck1KuUa.s:927 .text:000002d0 $d + /tmp/cck1KuUa.s:930 .text:000002d4 $t + /tmp/cck1KuUa.s:935 .text:000002d4 RCC_GetFlagStatus + /tmp/cck1KuUa.s:980 .text:000002fc $d + /tmp/cck1KuUa.s:983 .text:00000300 $t + /tmp/cck1KuUa.s:988 .text:00000300 RCC_WaitForHSEStartUp + /tmp/cck1KuUa.s:1024 .text:00000330 $d + /tmp/cck1KuUa.s:1027 .text:00000334 $t + /tmp/cck1KuUa.s:1032 .text:00000334 RCC_ClearFlag + /tmp/cck1KuUa.s:1048 .text:00000340 $d + /tmp/cck1KuUa.s:1051 .text:00000344 $t + /tmp/cck1KuUa.s:1056 .text:00000344 RCC_GetITStatus + /tmp/cck1KuUa.s:1076 .text:00000354 $d + /tmp/cck1KuUa.s:1079 .text:00000358 $t + /tmp/cck1KuUa.s:1084 .text:00000358 RCC_ClearITPendingBit + /tmp/cck1KuUa.s:1099 .text:00000360 $d + /tmp/cck1KuUa.s:1106 .rodata:00000000 APBAHBPrescTable + /tmp/cck1KuUa.s:1107 .rodata:00000000 $d + /tmp/cck1KuUa.s:1125 .rodata:00000010 ADCPrescTable + /tmp/cck1KuUa.s:1131 .bss:00000000 $d + /tmp/cck1KuUa.s:1135 .bss:00000000 HSEStatus + /tmp/cck1KuUa.s:1140 .bss:00000004 StartUpCounter + +NO UNDEFINED SYMBOLS diff --git a/src/stm32lib/src/stm32f10x_rtc.c b/src/stm32lib/src/stm32f10x_rtc.c new file mode 100644 index 0000000..55a8bea --- /dev/null +++ b/src/stm32lib/src/stm32f10x_rtc.c @@ -0,0 +1,320 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_rtc.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the RTC firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_rtc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define CRL_CNF_Set ((u16)0x0010) /* Configuration Flag Enable Mask */
+#define CRL_CNF_Reset ((u16)0xFFEF) /* Configuration Flag Disable Mask */
+#define RTC_LSB_Mask ((u32)0x0000FFFF) /* RTC LSB Mask */
+#define PRLH_MSB_Mask ((u32)0x000F0000) /* RTC Prescaler MSB Mask */
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : RTC_ITConfig
+* Description : Enables or disables the specified RTC interrupts.
+* Input : - RTC_IT: specifies the RTC interrupts sources to be enabled
+* or disabled.
+* This parameter can be any combination of the following values:
+* - RTC_IT_OW: Overflow interrupt
+* - RTC_IT_ALR: Alarm interrupt
+* - RTC_IT_SEC: Second interrupt
+* - NewState: new state of the specified RTC interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_ITConfig(u16 RTC_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_RTC_IT(RTC_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ RTC->CRH |= RTC_IT;
+ }
+ else
+ {
+ RTC->CRH &= (u16)~RTC_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : RTC_EnterConfigMode
+* Description : Enters the RTC configuration mode.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_EnterConfigMode(void)
+{
+ /* Set the CNF flag to enter in the Configuration Mode */
+ RTC->CRL |= CRL_CNF_Set;
+}
+
+/*******************************************************************************
+* Function Name : RTC_ExitConfigMode
+* Description : Exits from the RTC configuration mode.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_ExitConfigMode(void)
+{
+ /* Reset the CNF flag to exit from the Configuration Mode */
+ RTC->CRL &= CRL_CNF_Reset;
+}
+
+/*******************************************************************************
+* Function Name : RTC_GetCounter
+* Description : Gets the RTC counter value.
+* Input : None
+* Output : None
+* Return : RTC counter value.
+*******************************************************************************/
+u32 RTC_GetCounter(void)
+{
+ u16 tmp = 0;
+ tmp = RTC->CNTL;
+
+ return (((u32)RTC->CNTH << 16 ) | tmp) ;
+}
+
+/*******************************************************************************
+* Function Name : RTC_SetCounter
+* Description : Sets the RTC counter value.
+* Input : - CounterValue: RTC counter new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_SetCounter(u32 CounterValue)
+{
+ RTC_EnterConfigMode();
+
+ /* Set RTC COUNTER MSB word */
+ RTC->CNTH = CounterValue >> 16;
+ /* Set RTC COUNTER LSB word */
+ RTC->CNTL = (CounterValue & RTC_LSB_Mask);
+
+ RTC_ExitConfigMode();
+}
+
+/*******************************************************************************
+* Function Name : RTC_SetPrescaler
+* Description : Sets the RTC prescaler value.
+* Input : - PrescalerValue: RTC prescaler new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_SetPrescaler(u32 PrescalerValue)
+{
+ /* Check the parameters */
+ assert_param(IS_RTC_PRESCALER(PrescalerValue));
+
+ RTC_EnterConfigMode();
+
+ /* Set RTC PRESCALER MSB word */
+ RTC->PRLH = (PrescalerValue & PRLH_MSB_Mask) >> 16;
+ /* Set RTC PRESCALER LSB word */
+ RTC->PRLL = (PrescalerValue & RTC_LSB_Mask);
+
+ RTC_ExitConfigMode();
+}
+
+/*******************************************************************************
+* Function Name : RTC_SetAlarm
+* Description : Sets the RTC alarm value.
+* Input : - AlarmValue: RTC alarm new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_SetAlarm(u32 AlarmValue)
+{
+ RTC_EnterConfigMode();
+
+ /* Set the ALARM MSB word */
+ RTC->ALRH = AlarmValue >> 16;
+ /* Set the ALARM LSB word */
+ RTC->ALRL = (AlarmValue & RTC_LSB_Mask);
+
+ RTC_ExitConfigMode();
+}
+
+/*******************************************************************************
+* Function Name : RTC_GetDivider
+* Description : Gets the RTC divider value.
+* Input : None
+* Output : None
+* Return : RTC Divider value.
+*******************************************************************************/
+u32 RTC_GetDivider(void)
+{
+ u32 tmp = 0x00;
+
+ tmp = ((u32)RTC->DIVH & (u32)0x000F) << 16;
+ tmp |= RTC->DIVL;
+
+ return tmp;
+}
+
+/*******************************************************************************
+* Function Name : RTC_WaitForLastTask
+* Description : Waits until last write operation on RTC registers has finished.
+* This function must be called before any write to RTC registers.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_WaitForLastTask(void)
+{
+ /* Loop until RTOFF flag is set */
+ while ((RTC->CRL & RTC_FLAG_RTOFF) == (u16)RESET)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RTC_WaitForSynchro
+* Description : Waits until the RTC registers (RTC_CNT, RTC_ALR and RTC_PRL)
+* are synchronized with RTC APB clock.
+* This function must be called before any read operation after
+* an APB reset or an APB clock stop.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_WaitForSynchro(void)
+{
+ /* Clear RSF flag */
+ RTC->CRL &= (u16)~RTC_FLAG_RSF;
+
+ /* Loop until RSF flag is set */
+ while ((RTC->CRL & RTC_FLAG_RSF) == (u16)RESET)
+ {
+ }
+}
+
+/*******************************************************************************
+* Function Name : RTC_GetFlagStatus
+* Description : Checks whether the specified RTC flag is set or not.
+* Input : - RTC_FLAG: specifies the flag to check.
+* This parameter can be one the following values:
+* - RTC_FLAG_RTOFF: RTC Operation OFF flag
+* - RTC_FLAG_RSF: Registers Synchronized flag
+* - RTC_FLAG_OW: Overflow flag
+* - RTC_FLAG_ALR: Alarm flag
+* - RTC_FLAG_SEC: Second flag
+* Output : None
+* Return : The new state of RTC_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus RTC_GetFlagStatus(u16 RTC_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_RTC_GET_FLAG(RTC_FLAG));
+
+ if ((RTC->CRL & RTC_FLAG) != (u16)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : RTC_ClearFlag
+* Description : Clears the RTC’s pending flags.
+* Input : - RTC_FLAG: specifies the flag to clear.
+* This parameter can be any combination of the following values:
+* - RTC_FLAG_RSF: Registers Synchronized flag. This flag
+* is cleared only after an APB reset or an APB Clock stop.
+* - RTC_FLAG_OW: Overflow flag
+* - RTC_FLAG_ALR: Alarm flag
+* - RTC_FLAG_SEC: Second flag
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_ClearFlag(u16 RTC_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_RTC_CLEAR_FLAG(RTC_FLAG));
+
+ /* Clear the coressponding RTC flag */
+ RTC->CRL &= (u16)~RTC_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : RTC_GetITStatus
+* Description : Checks whether the specified RTC interrupt has occured or not.
+* Input : - RTC_IT: specifies the RTC interrupts sources to check.
+* This parameter can be one of the following values:
+* - RTC_IT_OW: Overflow interrupt
+* - RTC_IT_ALR: Alarm interrupt
+* - RTC_IT_SEC: Second interrupt
+* Output : None
+* Return : The new state of the RTC_IT (SET or RESET).
+*******************************************************************************/
+ITStatus RTC_GetITStatus(u16 RTC_IT)
+{
+ ITStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_RTC_GET_IT(RTC_IT));
+
+ bitstatus = (ITStatus)(RTC->CRL & RTC_IT);
+
+ if (((RTC->CRH & RTC_IT) != (u16)RESET) && (bitstatus != (u16)RESET))
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : RTC_ClearITPendingBit
+* Description : Clears the RTC’s interrupt pending bits.
+* Input : - RTC_IT: specifies the interrupt pending bit to clear.
+* This parameter can be any combination of the following values:
+* - RTC_IT_OW: Overflow interrupt
+* - RTC_IT_ALR: Alarm interrupt
+* - RTC_IT_SEC: Second interrupt
+* Output : None
+* Return : None
+*******************************************************************************/
+void RTC_ClearITPendingBit(u16 RTC_IT)
+{
+ /* Check the parameters */
+ assert_param(IS_RTC_IT(RTC_IT));
+
+ /* Clear the coressponding RTC pending bit */
+ RTC->CRL &= (u16)~RTC_IT;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_sdio.c b/src/stm32lib/src/stm32f10x_sdio.c new file mode 100644 index 0000000..b7da816 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_sdio.c @@ -0,0 +1,832 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_sdio.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the SDIO firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_sdio.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* ------------ SDIO registers bit address in the alias region ----------- */
+#define SDIO_OFFSET (SDIO_BASE - PERIPH_BASE)
+
+/* --- CLKCR Register ---*/
+/* Alias word address of CLKEN bit */
+#define CLKCR_OFFSET (SDIO_OFFSET + 0x04)
+#define CLKEN_BitNumber 0x08
+#define CLKCR_CLKEN_BB (PERIPH_BB_BASE + (CLKCR_OFFSET * 32) + (CLKEN_BitNumber * 4))
+
+/* --- CMD Register ---*/
+/* Alias word address of SDIOSUSPEND bit */
+#define CMD_OFFSET (SDIO_OFFSET + 0x0C)
+#define SDIOSUSPEND_BitNumber 0x0B
+#define CMD_SDIOSUSPEND_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (SDIOSUSPEND_BitNumber * 4))
+
+/* Alias word address of ENCMDCOMPL bit */
+#define ENCMDCOMPL_BitNumber 0x0C
+#define CMD_ENCMDCOMPL_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ENCMDCOMPL_BitNumber * 4))
+
+/* Alias word address of NIEN bit */
+#define NIEN_BitNumber 0x0D
+#define CMD_NIEN_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (NIEN_BitNumber * 4))
+
+/* Alias word address of ATACMD bit */
+#define ATACMD_BitNumber 0x0E
+#define CMD_ATACMD_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ATACMD_BitNumber * 4))
+
+/* --- DCTRL Register ---*/
+/* Alias word address of DMAEN bit */
+#define DCTRL_OFFSET (SDIO_OFFSET + 0x2C)
+#define DMAEN_BitNumber 0x03
+#define DCTRL_DMAEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (DMAEN_BitNumber * 4))
+
+/* Alias word address of RWSTART bit */
+#define RWSTART_BitNumber 0x08
+#define DCTRL_RWSTART_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTART_BitNumber * 4))
+
+/* Alias word address of RWSTOP bit */
+#define RWSTOP_BitNumber 0x09
+#define DCTRL_RWSTOP_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTOP_BitNumber * 4))
+
+/* Alias word address of RWMOD bit */
+#define RWMOD_BitNumber 0x0A
+#define DCTRL_RWMOD_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWMOD_BitNumber * 4))
+
+/* Alias word address of SDIOEN bit */
+#define SDIOEN_BitNumber 0x0B
+#define DCTRL_SDIOEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (SDIOEN_BitNumber * 4))
+
+
+/* ---------------------- SDIO registers bit mask ------------------------ */
+/* --- CLKCR Register ---*/
+/* CLKCR register clear mask */
+#define CLKCR_CLEAR_MASK ((u32)0xFFFF8100)
+
+/* --- PWRCTRL Register ---*/
+/* SDIO PWRCTRL Mask */
+#define PWR_PWRCTRL_MASK ((u32)0xFFFFFFFC)
+
+/* --- DCTRL Register ---*/
+/* SDIO DCTRL Clear Mask */
+#define DCTRL_CLEAR_MASK ((u32)0xFFFFFF08)
+
+/* --- CMD Register ---*/
+/* CMD Register clear mask */
+#define CMD_CLEAR_MASK ((u32)0xFFFFF800)
+
+/* SDIO RESP Registers Address */
+#define SDIO_RESP_ADDR ((u32)(SDIO_BASE + 0x14))
+
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : SDIO_DeInit
+* Description : Deinitializes the SDIO peripheral registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_DeInit(void)
+{
+ SDIO->POWER = 0x00000000;
+ SDIO->CLKCR = 0x00000000;
+ SDIO->ARG = 0x00000000;
+ SDIO->CMD = 0x00000000;
+ SDIO->DTIMER = 0x00000000;
+ SDIO->DLEN = 0x00000000;
+ SDIO->DCTRL = 0x00000000;
+ SDIO->ICR = 0x00C007FF;
+ SDIO->MASK = 0x00000000;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_Init
+* Description : Initializes the SDIO peripheral according to the specified
+* parameters in the SDIO_InitStruct.
+* Input : SDIO_InitStruct : pointer to a SDIO_InitTypeDef structure
+* that contains the configuration information for the SDIO
+* peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_SDIO_CLOCK_EDGE(SDIO_InitStruct->SDIO_ClockEdge));
+ assert_param(IS_SDIO_CLOCK_BYPASS(SDIO_InitStruct->SDIO_ClockBypass));
+ assert_param(IS_SDIO_CLOCK_POWER_SAVE(SDIO_InitStruct->SDIO_ClockPowerSave));
+ assert_param(IS_SDIO_BUS_WIDE(SDIO_InitStruct->SDIO_BusWide));
+ assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(SDIO_InitStruct->SDIO_HardwareFlowControl));
+
+/*---------------------------- SDIO CLKCR Configuration ------------------------*/
+ /* Get the SDIO CLKCR value */
+ tmpreg = SDIO->CLKCR;
+
+ /* Clear CLKDIV, PWRSAV, BYPASS, WIDBUS, NEGEDGE, HWFC_EN bits */
+ tmpreg &= CLKCR_CLEAR_MASK;
+
+ /* Set CLKDIV bits according to SDIO_ClockDiv value */
+ /* Set PWRSAV bit according to SDIO_ClockPowerSave value */
+ /* Set BYPASS bit according to SDIO_ClockBypass value */
+ /* Set WIDBUS bits according to SDIO_BusWide value */
+ /* Set NEGEDGE bits according to SDIO_ClockEdge value */
+ /* Set HWFC_EN bits according to SDIO_HardwareFlowControl value */
+ tmpreg |= (SDIO_InitStruct->SDIO_ClockDiv | SDIO_InitStruct->SDIO_ClockPowerSave |
+ SDIO_InitStruct->SDIO_ClockBypass | SDIO_InitStruct->SDIO_BusWide |
+ SDIO_InitStruct->SDIO_ClockEdge | SDIO_InitStruct->SDIO_HardwareFlowControl);
+
+ /* Write to SDIO CLKCR */
+ SDIO->CLKCR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_StructInit
+* Description : Fills each SDIO_InitStruct member with its default value.
+* Input : SDIO_InitStruct: pointer to an SDIO_InitTypeDef structure which
+* will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct)
+{
+ /* SDIO_InitStruct members default value */
+ SDIO_InitStruct->SDIO_ClockDiv = 0x00;
+ SDIO_InitStruct->SDIO_ClockEdge = SDIO_ClockEdge_Rising;
+ SDIO_InitStruct->SDIO_ClockBypass = SDIO_ClockBypass_Disable;
+ SDIO_InitStruct->SDIO_ClockPowerSave = SDIO_ClockPowerSave_Disable;
+ SDIO_InitStruct->SDIO_BusWide = SDIO_BusWide_1b;
+ SDIO_InitStruct->SDIO_HardwareFlowControl = SDIO_HardwareFlowControl_Disable;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_ClockCmd
+* Description : Enables or disables the SDIO Clock.
+* Input : NewState: new state of the SDIO Clock.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_ClockCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CLKCR_CLKEN_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_SetPowerState
+* Description : Sets the power status of the controller.
+* Input : SDIO_PowerState: new state of the Power state.
+* This parameter can be one of the following values:
+* - SDIO_PowerState_OFF
+* - SDIO_PowerState_ON
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_SetPowerState(u32 SDIO_PowerState)
+{
+ /* Check the parameters */
+ assert_param(IS_SDIO_POWER_STATE(SDIO_PowerState));
+
+ SDIO->POWER &= PWR_PWRCTRL_MASK;
+ SDIO->POWER |= SDIO_PowerState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_GetPowerState
+* Description : Gets the power status of the controller.
+* Input : None
+* Output : None
+* Return : Power status of the controller. The returned value can
+* be one of the following:
+* - 0x00: Power OFF
+* - 0x02: Power UP
+* - 0x03: Power ON
+*******************************************************************************/
+u32 SDIO_GetPowerState(void)
+{
+ return (SDIO->POWER & (~PWR_PWRCTRL_MASK));
+}
+
+/*******************************************************************************
+* Function Name : SDIO_ITConfig
+* Description : Enables or disables the SDIO interrupts.
+* Input : - SDIO_IT: specifies the SDIO interrupt sources to be
+* enabled or disabled.
+* This parameter can be one or a combination of the following
+* values:
+* - SDIO_IT_CCRCFAIL: Command response received (CRC check
+* failed) interrupt
+* - SDIO_IT_DCRCFAIL: Data block sent/received (CRC check
+* failed) interrupt
+* - SDIO_IT_CTIMEOUT: Command response timeout interrupt
+* - SDIO_IT_DTIMEOUT: Data timeout interrupt
+* - SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt
+* - SDIO_IT_RXOVERR: Received FIFO overrun error interrupt
+* - SDIO_IT_CMDREND: Command response received (CRC check
+* passed) interrupt
+* - SDIO_IT_CMDSENT: Command sent (no response required)
+* interrupt
+* - SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is
+* zero) interrupt
+* - SDIO_IT_STBITERR: Start bit not detected on all data
+* signals in wide bus mode interrupt
+* - SDIO_IT_DBCKEND: Data block sent/received (CRC check
+* passed) interrupt
+* - SDIO_IT_CMDACT: Command transfer in progress interrupt
+* - SDIO_IT_TXACT: Data transmit in progress interrupt
+* - SDIO_IT_RXACT: Data receive in progress interrupt
+* - SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt
+* - SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt
+* - SDIO_IT_TXFIFOF: Transmit FIFO full interrupt
+* - SDIO_IT_RXFIFOF: Receive FIFO full interrupt
+* - SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt
+* - SDIO_IT_RXFIFOE: Receive FIFO empty interrupt
+* - SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt
+* - SDIO_IT_RXDAVL: Data available in receive FIFO interrupt
+* - SDIO_IT_SDIOIT: SD I/O interrupt received interrupt
+* - SDIO_IT_CEATAEND: CE-ATA command completion signal
+* received for CMD61 interrupt
+* - NewState: new state of the specified SDIO interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_ITConfig(u32 SDIO_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_SDIO_IT(SDIO_IT));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the SDIO interrupts */
+ SDIO->MASK |= SDIO_IT;
+ }
+ else
+ {
+ /* Disable the SDIO interrupts */
+ SDIO->MASK &= ~SDIO_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SDIO_DMACmd
+* Description : Enables or disables the SDIO DMA request.
+* Input : NewState: new state of the selected SDIO DMA request.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_DMACmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) DCTRL_DMAEN_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_SendCommand
+* Description : Initializes the SDIO Command according to the specified
+* parameters in the SDIO_CmdInitStruct and send the command.
+* Input : SDIO_CmdInitStruct : pointer to a SDIO_CmdInitTypeDef
+* structure that contains the configuration information
+* for the SDIO command.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_SDIO_CMD_INDEX(SDIO_CmdInitStruct->SDIO_CmdIndex));
+ assert_param(IS_SDIO_RESPONSE(SDIO_CmdInitStruct->SDIO_Response));
+ assert_param(IS_SDIO_WAIT(SDIO_CmdInitStruct->SDIO_Wait));
+ assert_param(IS_SDIO_CPSM(SDIO_CmdInitStruct->SDIO_CPSM));
+
+/*---------------------------- SDIO ARG Configuration ------------------------*/
+ /* Set the SDIO Argument value */
+ SDIO->ARG = SDIO_CmdInitStruct->SDIO_Argument;
+
+/*---------------------------- SDIO CMD Configuration ------------------------*/
+ /* Get the SDIO CMD value */
+ tmpreg = SDIO->CMD;
+
+ /* Clear CMDINDEX, WAITRESP, WAITINT, WAITPEND, CPSMEN bits */
+ tmpreg &= CMD_CLEAR_MASK;
+ /* Set CMDINDEX bits according to SDIO_CmdIndex value */
+ /* Set WAITRESP bits according to SDIO_Response value */
+ /* Set WAITINT and WAITPEND bits according to SDIO_Wait value */
+ /* Set CPSMEN bits according to SDIO_CPSM value */
+ tmpreg |= (u32)SDIO_CmdInitStruct->SDIO_CmdIndex | SDIO_CmdInitStruct->SDIO_Response
+ | SDIO_CmdInitStruct->SDIO_Wait | SDIO_CmdInitStruct->SDIO_CPSM;
+
+ /* Write to SDIO CMD */
+ SDIO->CMD = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_CmdStructInit
+* Description : Fills each SDIO_CmdInitStruct member with its default value.
+* Input : SDIO_CmdInitStruct: pointer to an SDIO_CmdInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct)
+{
+ /* SDIO_CmdInitStruct members default value */
+ SDIO_CmdInitStruct->SDIO_Argument = 0x00;
+ SDIO_CmdInitStruct->SDIO_CmdIndex = 0x00;
+ SDIO_CmdInitStruct->SDIO_Response = SDIO_Response_No;
+ SDIO_CmdInitStruct->SDIO_Wait = SDIO_Wait_No;
+ SDIO_CmdInitStruct->SDIO_CPSM = SDIO_CPSM_Disable;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_GetCommandResponse
+* Description : Returns command index of last command for which response
+* received.
+* Input : None
+* Output : None
+* Return : Returns the command index of the last command response received.
+*******************************************************************************/
+u8 SDIO_GetCommandResponse(void)
+{
+ return (u8)(SDIO->RESPCMD);
+}
+
+/*******************************************************************************
+* Function Name : SDIO_GetResponse
+* Description : Returns response received from the card for the last command.
+* Input : - SDIO_RESP: Specifies the SDIO response register.
+* This parameter can be one of the following values:
+* - SDIO_RESP1: Response Register 1
+* - SDIO_RESP2: Response Register 2
+* - SDIO_RESP3: Response Register 3
+* - SDIO_RESP4: Response Register 4
+* Output : None
+* Return : The Corresponding response register value.
+*******************************************************************************/
+u32 SDIO_GetResponse(u32 SDIO_RESP)
+{
+ /* Check the parameters */
+ assert_param(IS_SDIO_RESP(SDIO_RESP));
+
+ return (*(vu32 *)(SDIO_RESP_ADDR + SDIO_RESP));
+}
+
+/*******************************************************************************
+* Function Name : SDIO_DataConfig
+* Description : Initializes the SDIO data path according to the specified
+* parameters in the SDIO_DataInitStruct.
+* Input : SDIO_DataInitStruct : pointer to a SDIO_DataInitTypeDef
+* structure that contains the configuration information
+* for the SDIO command.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_SDIO_DATA_LENGTH(SDIO_DataInitStruct->SDIO_DataLength));
+ assert_param(IS_SDIO_BLOCK_SIZE(SDIO_DataInitStruct->SDIO_DataBlockSize));
+ assert_param(IS_SDIO_TRANSFER_DIR(SDIO_DataInitStruct->SDIO_TransferDir));
+ assert_param(IS_SDIO_TRANSFER_MODE(SDIO_DataInitStruct->SDIO_TransferMode));
+ assert_param(IS_SDIO_DPSM(SDIO_DataInitStruct->SDIO_DPSM));
+
+/*---------------------------- SDIO DTIMER Configuration ---------------------*/
+ /* Set the SDIO Data TimeOut value */
+ SDIO->DTIMER = SDIO_DataInitStruct->SDIO_DataTimeOut;
+
+/*---------------------------- SDIO DLEN Configuration -----------------------*/
+ /* Set the SDIO DataLength value */
+ SDIO->DLEN = SDIO_DataInitStruct->SDIO_DataLength;
+
+/*---------------------------- SDIO DCTRL Configuration ----------------------*/
+ /* Get the SDIO DCTRL value */
+ tmpreg = SDIO->DCTRL;
+
+ /* Clear DEN, DTMODE, DTDIR and DBCKSIZE bits */
+ tmpreg &= DCTRL_CLEAR_MASK;
+ /* Set DEN bit according to SDIO_DPSM value */
+ /* Set DTMODE bit according to SDIO_TransferMode value */
+ /* Set DTDIR bit according to SDIO_TransferDir value */
+ /* Set DBCKSIZE bits according to SDIO_DataBlockSize value */
+ tmpreg |= (u32)SDIO_DataInitStruct->SDIO_DataBlockSize | SDIO_DataInitStruct->SDIO_TransferDir
+ | SDIO_DataInitStruct->SDIO_TransferMode | SDIO_DataInitStruct->SDIO_DPSM;
+
+ /* Write to SDIO DCTRL */
+ SDIO->DCTRL = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_DataStructInit
+* Description : Fills each SDIO_DataInitStruct member with its default value.
+* Input : SDIO_DataInitStruct: pointer to an SDIO_DataInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct)
+{
+ /* SDIO_DataInitStruct members default value */
+ SDIO_DataInitStruct->SDIO_DataTimeOut = 0xFFFFFFFF;
+ SDIO_DataInitStruct->SDIO_DataLength = 0x00;
+ SDIO_DataInitStruct->SDIO_DataBlockSize = SDIO_DataBlockSize_1b;
+ SDIO_DataInitStruct->SDIO_TransferDir = SDIO_TransferDir_ToCard;
+ SDIO_DataInitStruct->SDIO_TransferMode = SDIO_TransferMode_Block;
+ SDIO_DataInitStruct->SDIO_DPSM = SDIO_DPSM_Disable;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_GetDataCounter
+* Description : Returns number of remaining data bytes to be transferred.
+* Input : None
+* Output : None
+* Return : Number of remaining data bytes to be transferred
+*******************************************************************************/
+u32 SDIO_GetDataCounter(void)
+{
+ return SDIO->DCOUNT;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_ReadData
+* Description : Read one data word from Rx FIFO.
+* Input : None
+* Output : None
+* Return : Data received
+*******************************************************************************/
+u32 SDIO_ReadData(void)
+{
+ return SDIO->FIFO;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_WriteData
+* Description : Write one data word to Tx FIFO.
+* Input : Data: 32-bit data word to write.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_WriteData(u32 Data)
+{
+ SDIO->FIFO = Data;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_GetFIFOCount
+* Description : Returns the number of words left to be written to or read
+* from FIFO.
+* Input : None
+* Output : None
+* Return : Remaining number of words.
+*******************************************************************************/
+u32 SDIO_GetFIFOCount(void)
+{
+ return SDIO->FIFOCNT;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_StartSDIOReadWait
+* Description : Starts the SD I/O Read Wait operation.
+* Input : NewState: new state of the Start SDIO Read Wait operation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_StartSDIOReadWait(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) DCTRL_RWSTART_BB = (u32) NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_StopSDIOReadWait
+* Description : Stops the SD I/O Read Wait operation.
+* Input : NewState: new state of the Stop SDIO Read Wait operation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_StopSDIOReadWait(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) DCTRL_RWSTOP_BB = (u32) NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_SetSDIOReadWaitMode
+* Description : Sets one of the two options of inserting read wait interval.
+* Input : SDIOReadWaitMode: SD I/O Read Wait operation mode.
+* This parametre can be:
+* - SDIO_ReadWaitMode_CLK: Read Wait control by stopping SDIOCLK
+* - SDIO_ReadWaitMode_DATA2: Read Wait control using SDIO_DATA2
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_SetSDIOReadWaitMode(u32 SDIO_ReadWaitMode)
+{
+ /* Check the parameters */
+ assert_param(IS_SDIO_READWAIT_MODE(SDIO_ReadWaitMode));
+
+ *(vu32 *) DCTRL_RWMOD_BB = SDIO_ReadWaitMode;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_SetSDIOOperation
+* Description : Enables or disables the SD I/O Mode Operation.
+* Input : NewState: new state of SDIO specific operation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_SetSDIOOperation(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) DCTRL_SDIOEN_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_SendSDIOSuspendCmd
+* Description : Enables or disables the SD I/O Mode suspend command sending.
+* Input : NewState: new state of the SD I/O Mode suspend command.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_SendSDIOSuspendCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CMD_SDIOSUSPEND_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_CommandCompletionCmd
+* Description : Enables or disables the command completion signal.
+* Input : NewState: new state of command completion signal.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_CommandCompletionCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CMD_ENCMDCOMPL_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_CEATAITCmd
+* Description : Enables or disables the CE-ATA interrupt.
+* Input : NewState: new state of CE-ATA interrupt.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_CEATAITCmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CMD_NIEN_BB = (u32)((~((u32)NewState)) & ((u32)0x1));
+}
+
+/*******************************************************************************
+* Function Name : SDIO_SendCEATACmd
+* Description : Sends CE-ATA command (CMD61).
+* Input : NewState: new state of CE-ATA command.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_SendCEATACmd(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ *(vu32 *) CMD_ATACMD_BB = (u32)NewState;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_GetFlagStatus
+* Description : Checks whether the specified SDIO flag is set or not.
+* Input : SDIO_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - SDIO_FLAG_CCRCFAIL: Command response received (CRC check
+* failed)
+* - SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check
+* failed)
+* - SDIO_FLAG_CTIMEOUT: Command response timeout
+* - SDIO_FLAG_DTIMEOUT: Data timeou
+* - SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error
+* - SDIO_FLAG_RXOVERR: Received FIFO overrun error
+* - SDIO_FLAG_CMDREND: Command response received (CRC check
+* passed)
+* - SDIO_FLAG_CMDSENT: Command sent (no response required)
+* - SDIO_FLAG_DATAEND: Data end (data counter, SDIDCOUNT, is
+* zero)
+* - SDIO_FLAG_STBITERR: Start bit not detected on all data
+* signals in wide bus mode
+* - SDIO_FLAG_DBCKEND: Data block sent/received (CRC check
+* passed)
+* - SDIO_FLAG_CMDACT: Command transfer in progress
+* - SDIO_FLAG_TXACT: Data transmit in progress
+* - SDIO_FLAG_RXACT: Data receive in progress
+* - SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty
+* - SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full
+* - SDIO_FLAG_TXFIFOF: Transmit FIFO full
+* - SDIO_FLAG_RXFIFOF: Receive FIFO full
+* - SDIO_FLAG_TXFIFOE: Transmit FIFO empty
+* - SDIO_FLAG_RXFIFOE: Receive FIFO empty
+* - SDIO_FLAG_TXDAVL: Data available in transmit FIFO
+* - SDIO_FLAG_RXDAVL: Data available in receive FIFO
+* - SDIO_FLAG_SDIOIT: SD I/O interrupt received
+* - SDIO_FLAG_CEATAEND: CE-ATA command completion signal
+* received for CMD61
+* Output : None
+* Return : The new state of SDIO_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus SDIO_GetFlagStatus(u32 SDIO_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_SDIO_FLAG(SDIO_FLAG));
+
+ if ((SDIO->STA & SDIO_FLAG) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_ClearFlag
+* Description : Clears the SDIO's pending flags.
+* Input : SDIO_FLAG: specifies the flag to clear.
+* This parameter can be one or a combination of the following
+* values:
+* - SDIO_FLAG_CCRCFAIL: Command response received (CRC check
+* failed)
+* - SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check
+* failed)
+* - SDIO_FLAG_CTIMEOUT: Command response timeout
+* - SDIO_FLAG_DTIMEOUT: Data timeou
+* - SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error
+* - SDIO_FLAG_RXOVERR: Received FIFO overrun error
+* - SDIO_FLAG_CMDREND: Command response received (CRC check
+* passed)
+* - SDIO_FLAG_CMDSENT: Command sent (no response required)
+* - SDIO_FLAG_DATAEND: Data end (data counter, SDIDCOUNT, is
+* zero)
+* - SDIO_FLAG_STBITERR: Start bit not detected on all data
+* signals in wide bus mode
+* - SDIO_FLAG_DBCKEND: Data block sent/received (CRC check
+* passed)
+* - SDIO_FLAG_SDIOIT: SD I/O interrupt received
+* - SDIO_FLAG_CEATAEND: CE-ATA command completion signal
+* received for CMD61
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_ClearFlag(u32 SDIO_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_SDIO_CLEAR_FLAG(SDIO_FLAG));
+
+ SDIO->ICR = SDIO_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_GetITStatus
+* Description : Checks whether the specified SDIO interrupt has occurred or not.
+* Input : SDIO_IT: specifies the SDIO interrupt source to check.
+* This parameter can be one of the following values:
+* - SDIO_IT_CCRCFAIL: Command response received (CRC check
+* failed) interrupt
+* - SDIO_IT_DCRCFAIL: Data block sent/received (CRC check
+* failed) interrupt
+* - SDIO_IT_CTIMEOUT: Command response timeout interrupt
+* - SDIO_IT_DTIMEOUT: Data timeout interrupt
+* - SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt
+* - SDIO_IT_RXOVERR: Received FIFO overrun error interrupt
+* - SDIO_IT_CMDREND: Command response received (CRC check
+* passed) interrupt
+* - SDIO_IT_CMDSENT: Command sent (no response required)
+* interrupt
+* - SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is
+* zero) interrupt
+* - SDIO_IT_STBITERR: Start bit not detected on all data
+* signals in wide bus mode interrupt
+* - SDIO_IT_DBCKEND: Data block sent/received (CRC check
+* passed) interrupt
+* - SDIO_IT_CMDACT: Command transfer in progress interrupt
+* - SDIO_IT_TXACT: Data transmit in progress interrupt
+* - SDIO_IT_RXACT: Data receive in progress interrupt
+* - SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt
+* - SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt
+* - SDIO_IT_TXFIFOF: Transmit FIFO full interrupt
+* - SDIO_IT_RXFIFOF: Receive FIFO full interrupt
+* - SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt
+* - SDIO_IT_RXFIFOE: Receive FIFO empty interrupt
+* - SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt
+* - SDIO_IT_RXDAVL: Data available in receive FIFO interrupt
+* - SDIO_IT_SDIOIT: SD I/O interrupt received interrupt
+* - SDIO_IT_CEATAEND: CE-ATA command completion signal
+* received for CMD61 interrupt
+* Output : None
+* Return : The new state of SDIO_IT (SET or RESET).
+*******************************************************************************/
+ITStatus SDIO_GetITStatus(u32 SDIO_IT)
+{
+ ITStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_SDIO_GET_IT(SDIO_IT));
+
+ if ((SDIO->STA & SDIO_IT) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : SDIO_ClearITPendingBit
+* Description : Clears the SDIO’s interrupt pending bits.
+* Input : SDIO_IT: specifies the interrupt pending bit to clear.
+* This parameter can be one or a combination of the following
+* values:
+* - SDIO_IT_CCRCFAIL: Command response received (CRC check
+* failed) interrupt
+* - SDIO_IT_DCRCFAIL: Data block sent/received (CRC check
+* failed) interrupt
+* - SDIO_IT_CTIMEOUT: Command response timeout interrupt
+* - SDIO_IT_DTIMEOUT: Data timeout interrupt
+* - SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt
+* - SDIO_IT_RXOVERR: Received FIFO overrun error interrupt
+* - SDIO_IT_CMDREND: Command response received (CRC check
+* passed) interrupt
+* - SDIO_IT_CMDSENT: Command sent (no response required)
+* interrupt
+* - SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is
+* zero) interrupt
+* - SDIO_IT_STBITERR: Start bit not detected on all data
+* signals in wide bus mode interrupt
+* - SDIO_IT_SDIOIT: SD I/O interrupt received interrupt
+* - SDIO_IT_CEATAEND: CE-ATA command completion signal
+* received for CMD61
+* Output : None
+* Return : None
+*******************************************************************************/
+void SDIO_ClearITPendingBit(u32 SDIO_IT)
+{
+ /* Check the parameters */
+ assert_param(IS_SDIO_CLEAR_IT(SDIO_IT));
+
+ SDIO->ICR = SDIO_IT;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_spi.c b/src/stm32lib/src/stm32f10x_spi.c new file mode 100644 index 0000000..d914c09 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_spi.c @@ -0,0 +1,863 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_spi.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the SPI firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_spi.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* SPI SPE mask */
+#define CR1_SPE_Set ((u16)0x0040)
+#define CR1_SPE_Reset ((u16)0xFFBF)
+
+/* I2S I2SE mask */
+#define I2SCFGR_I2SE_Set ((u16)0x0400)
+#define I2SCFGR_I2SE_Reset ((u16)0xFBFF)
+
+/* SPI CRCNext mask */
+#define CR1_CRCNext_Set ((u16)0x1000)
+
+/* SPI CRCEN mask */
+#define CR1_CRCEN_Set ((u16)0x2000)
+#define CR1_CRCEN_Reset ((u16)0xDFFF)
+
+/* SPI SSOE mask */
+#define CR2_SSOE_Set ((u16)0x0004)
+#define CR2_SSOE_Reset ((u16)0xFFFB)
+
+/* SPI registers Masks */
+#define CR1_CLEAR_Mask ((u16)0x3040)
+#define I2SCFGR_CLEAR_Mask ((u16)0xF040)
+
+/* SPI or I2S mode selection masks */
+#define SPI_Mode_Select ((u16)0xF7FF)
+#define I2S_Mode_Select ((u16)0x0800)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : SPI_I2S_DeInit
+* Description : Deinitializes the SPIx peripheral registers to their default
+* reset values (Affects also the I2Ss).
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_I2S_DeInit(SPI_TypeDef* SPIx)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+
+ switch (*(u32*)&SPIx)
+ {
+ case SPI1_BASE:
+ /* Enable SPI1 reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE);
+ /* Release SPI1 from reset state */
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, DISABLE);
+ break;
+
+ case SPI2_BASE:
+ /* Enable SPI2 reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE);
+ /* Release SPI2 from reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, DISABLE);
+ break;
+
+ case SPI3_BASE:
+ /* Enable SPI3 reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE);
+ /* Release SPI3 from reset state */
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, DISABLE);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_Init
+* Description : Initializes the SPIx peripheral according to the specified
+* parameters in the SPI_InitStruct.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - SPI_InitStruct: pointer to a SPI_InitTypeDef structure that
+* contains the configuration information for the specified
+* SPI peripheral.
+* Output : None
+* Return : None
+******************************************************************************/
+void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct)
+{
+ u16 tmpreg = 0;
+
+ /* check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+
+ /* Check the SPI parameters */
+ assert_param(IS_SPI_DIRECTION_MODE(SPI_InitStruct->SPI_Direction));
+ assert_param(IS_SPI_MODE(SPI_InitStruct->SPI_Mode));
+ assert_param(IS_SPI_DATASIZE(SPI_InitStruct->SPI_DataSize));
+ assert_param(IS_SPI_CPOL(SPI_InitStruct->SPI_CPOL));
+ assert_param(IS_SPI_CPHA(SPI_InitStruct->SPI_CPHA));
+ assert_param(IS_SPI_NSS(SPI_InitStruct->SPI_NSS));
+ assert_param(IS_SPI_BAUDRATE_PRESCALER(SPI_InitStruct->SPI_BaudRatePrescaler));
+ assert_param(IS_SPI_FIRST_BIT(SPI_InitStruct->SPI_FirstBit));
+ assert_param(IS_SPI_CRC_POLYNOMIAL(SPI_InitStruct->SPI_CRCPolynomial));
+
+/*---------------------------- SPIx CR1 Configuration ------------------------*/
+ /* Get the SPIx CR1 value */
+ tmpreg = SPIx->CR1;
+ /* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */
+ tmpreg &= CR1_CLEAR_Mask;
+ /* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler
+ master/salve mode, CPOL and CPHA */
+ /* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */
+ /* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */
+ /* Set LSBFirst bit according to SPI_FirstBit value */
+ /* Set BR bits according to SPI_BaudRatePrescaler value */
+ /* Set CPOL bit according to SPI_CPOL value */
+ /* Set CPHA bit according to SPI_CPHA value */
+ tmpreg |= (u16)((u32)SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode |
+ SPI_InitStruct->SPI_DataSize | SPI_InitStruct->SPI_CPOL |
+ SPI_InitStruct->SPI_CPHA | SPI_InitStruct->SPI_NSS |
+ SPI_InitStruct->SPI_BaudRatePrescaler | SPI_InitStruct->SPI_FirstBit);
+ /* Write to SPIx CR1 */
+ SPIx->CR1 = tmpreg;
+
+ /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */
+ SPIx->I2SCFGR &= SPI_Mode_Select;
+
+/*---------------------------- SPIx CRCPOLY Configuration --------------------*/
+ /* Write to SPIx CRCPOLY */
+ SPIx->CRCPR = SPI_InitStruct->SPI_CRCPolynomial;
+}
+
+/*******************************************************************************
+* Function Name : I2S_Init
+* Description : Initializes the SPIx peripheral according to the specified
+* parameters in the I2S_InitStruct.
+* Input : - SPIx: where x can be 2 or 3 to select the SPI peripheral
+* (configured in I2S mode).
+* - I2S_InitStruct: pointer to an I2S_InitTypeDef structure that
+* contains the configuration information for the specified
+* SPI peripheral configured in I2S mode.
+* Output : None
+* Return : None
+******************************************************************************/
+void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct)
+{
+ u16 tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1;
+ u32 tmp = 0;
+ RCC_ClocksTypeDef RCC_Clocks;
+
+ /* Check the I2S parameters */
+ assert_param(IS_SPI_23_PERIPH(SPIx));
+ assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode));
+ assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard));
+ assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat));
+ assert_param(IS_I2S_MCLK_OUTPUT(I2S_InitStruct->I2S_MCLKOutput));
+ assert_param(IS_I2S_AUDIO_FREQ(I2S_InitStruct->I2S_AudioFreq));
+ assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL));
+
+/*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/
+
+ /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */
+ SPIx->I2SCFGR &= I2SCFGR_CLEAR_Mask;
+ SPIx->I2SPR = 0x0002;
+
+ /* Get the I2SCFGR register value */
+ tmpreg = SPIx->I2SCFGR;
+
+ /* If the default value has to be written, reinitialize i2sdiv and i2sodd*/
+ if(I2S_InitStruct->I2S_AudioFreq == I2S_AudioFreq_Default)
+ {
+ i2sodd = (u16)0;
+ i2sdiv = (u16)2;
+ }
+ /* If the requested audio frequency is not the default, compute the prescaler */
+ else
+ {
+ /* Check the frame length (For the Prescaler computing) */
+ if(I2S_InitStruct->I2S_DataFormat == I2S_DataFormat_16b)
+ {
+ /* Packet length is 16 bits */
+ packetlength = 1;
+ }
+ else
+ {
+ /* Packet length is 32 bits */
+ packetlength = 2;
+ }
+ /* Get System Clock frequency */
+ RCC_GetClocksFreq(&RCC_Clocks);
+
+ /* Compute the Real divider depending on the MCLK output state with a flaoting point */
+ if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable)
+ {
+ /* MCLK output is enabled */
+ tmp = (u16)(((10 * RCC_Clocks.SYSCLK_Frequency) / (256 * I2S_InitStruct->I2S_AudioFreq)) + 5);
+ }
+ else
+ {
+ /* MCLK output is disabled */
+ tmp = (u16)(((10 * RCC_Clocks.SYSCLK_Frequency) / (32 * packetlength * I2S_InitStruct->I2S_AudioFreq)) + 5);
+ }
+
+ /* Remove the flaoting point */
+ tmp = tmp/10;
+
+ /* Check the parity of the divider */
+ i2sodd = (u16)(tmp & (u16)0x0001);
+
+ /* Compute the i2sdiv prescaler */
+ i2sdiv = (u16)((tmp - i2sodd) / 2);
+
+ /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */
+ i2sodd = (u16) (i2sodd << 8);
+ }
+
+ /* Test if the divider is 1 or 0 */
+ if ((i2sdiv < 2) || (i2sdiv > 0xFF))
+ {
+ /* Set the default values */
+ i2sdiv = 2;
+ i2sodd = 0;
+ }
+
+ /* Write to SPIx I2SPR register the computed value */
+ SPIx->I2SPR = (u16)(i2sdiv | i2sodd | I2S_InitStruct->I2S_MCLKOutput);
+
+ /* Configure the I2S with the SPI_InitStruct values */
+ tmpreg |= (u16)(I2S_Mode_Select | I2S_InitStruct->I2S_Mode | \
+ I2S_InitStruct->I2S_Standard | I2S_InitStruct->I2S_DataFormat | \
+ I2S_InitStruct->I2S_CPOL);
+
+ /* Write to SPIx I2SCFGR */
+ SPIx->I2SCFGR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : SPI_StructInit
+* Description : Fills each SPI_InitStruct member with its default value.
+* Input : - SPI_InitStruct : pointer to a SPI_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct)
+{
+/*--------------- Reset SPI init structure parameters values -----------------*/
+ /* Initialize the SPI_Direction member */
+ SPI_InitStruct->SPI_Direction = SPI_Direction_2Lines_FullDuplex;
+
+ /* initialize the SPI_Mode member */
+ SPI_InitStruct->SPI_Mode = SPI_Mode_Slave;
+
+ /* initialize the SPI_DataSize member */
+ SPI_InitStruct->SPI_DataSize = SPI_DataSize_8b;
+
+ /* Initialize the SPI_CPOL member */
+ SPI_InitStruct->SPI_CPOL = SPI_CPOL_Low;
+
+ /* Initialize the SPI_CPHA member */
+ SPI_InitStruct->SPI_CPHA = SPI_CPHA_1Edge;
+
+ /* Initialize the SPI_NSS member */
+ SPI_InitStruct->SPI_NSS = SPI_NSS_Hard;
+
+ /* Initialize the SPI_BaudRatePrescaler member */
+ SPI_InitStruct->SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2;
+
+ /* Initialize the SPI_FirstBit member */
+ SPI_InitStruct->SPI_FirstBit = SPI_FirstBit_MSB;
+
+ /* Initialize the SPI_CRCPolynomial member */
+ SPI_InitStruct->SPI_CRCPolynomial = 7;
+}
+
+/*******************************************************************************
+* Function Name : I2S_StructInit
+* Description : Fills each I2S_InitStruct member with its default value.
+* Input : - I2S_InitStruct : pointer to a I2S_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct)
+{
+/*--------------- Reset I2S init structure parameters values -----------------*/
+ /* Initialize the I2S_Mode member */
+ I2S_InitStruct->I2S_Mode = I2S_Mode_SlaveTx;
+
+ /* Initialize the I2S_Standard member */
+ I2S_InitStruct->I2S_Standard = I2S_Standard_Phillips;
+
+ /* Initialize the I2S_DataFormat member */
+ I2S_InitStruct->I2S_DataFormat = I2S_DataFormat_16b;
+
+ /* Initialize the I2S_MCLKOutput member */
+ I2S_InitStruct->I2S_MCLKOutput = I2S_MCLKOutput_Disable;
+
+ /* Initialize the I2S_AudioFreq member */
+ I2S_InitStruct->I2S_AudioFreq = I2S_AudioFreq_Default;
+
+ /* Initialize the I2S_CPOL member */
+ I2S_InitStruct->I2S_CPOL = I2S_CPOL_Low;
+}
+
+/*******************************************************************************
+* Function Name : SPI_Cmd
+* Description : Enables or disables the specified SPI peripheral.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - NewState: new state of the SPIx peripheral.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected SPI peripheral */
+ SPIx->CR1 |= CR1_SPE_Set;
+ }
+ else
+ {
+ /* Disable the selected SPI peripheral */
+ SPIx->CR1 &= CR1_SPE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : I2S_Cmd
+* Description : Enables or disables the specified SPI peripheral (in I2S mode).
+* Input : - SPIx: where x can be 2 or 3 to select the SPI peripheral.
+* - NewState: new state of the SPIx peripheral.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_23_PERIPH(SPIx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected SPI peripheral (in I2S mode) */
+ SPIx->I2SCFGR |= I2SCFGR_I2SE_Set;
+ }
+ else
+ {
+ /* Disable the selected SPI peripheral (in I2S mode) */
+ SPIx->I2SCFGR &= I2SCFGR_I2SE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_ITConfig
+* Description : Enables or disables the specified SPI/I2S interrupts.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - 2 or 3 in I2S mode
+* - SPI_I2S_IT: specifies the SPI/I2S interrupt source to be
+* enabled or disabled.
+* This parameter can be one of the following values:
+* - SPI_I2S_IT_TXE: Tx buffer empty interrupt mask
+* - SPI_I2S_IT_RXNE: Rx buffer not empty interrupt mask
+* - SPI_I2S_IT_ERR: Error interrupt mask
+* - NewState: new state of the specified SPI/I2S interrupt.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, u8 SPI_I2S_IT, FunctionalState NewState)
+{
+ u16 itpos = 0, itmask = 0 ;
+
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+ assert_param(IS_SPI_I2S_CONFIG_IT(SPI_I2S_IT));
+
+ /* Get the SPI/I2S IT index */
+ itpos = SPI_I2S_IT >> 4;
+ /* Set the IT mask */
+ itmask = (u16)((u16)1 << itpos);
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected SPI/I2S interrupt */
+ SPIx->CR2 |= itmask;
+ }
+ else
+ {
+ /* Disable the selected SPI/I2S interrupt */
+ SPIx->CR2 &= (u16)~itmask;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_DMACmd
+* Description : Enables or disables the SPIx/I2Sx DMA interface.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - 2 or 3 in I2S mode
+* - SPI_I2S_DMAReq: specifies the SPI/I2S DMA transfer request
+* to be enabled or disabled.
+* This parameter can be any combination of the following values:
+* - SPI_I2S_DMAReq_Tx: Tx buffer DMA transfer request
+* - SPI_I2S_DMAReq_Rx: Rx buffer DMA transfer request
+* - NewState: new state of the selected SPI/I2S DMA transfer
+* request.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, u16 SPI_I2S_DMAReq, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+ assert_param(IS_SPI_I2S_DMAREQ(SPI_I2S_DMAReq));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected SPI/I2S DMA requests */
+ SPIx->CR2 |= SPI_I2S_DMAReq;
+ }
+ else
+ {
+ /* Disable the selected SPI/I2S DMA requests */
+ SPIx->CR2 &= (u16)~SPI_I2S_DMAReq;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_SendData
+* Description : Transmits a Data through the SPIx/I2Sx peripheral.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - 2 or 3 in I2S mode
+* - Data : Data to be transmitted..
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_I2S_SendData(SPI_TypeDef* SPIx, u16 Data)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+
+ /* Write in the DR register the data to be sent */
+ SPIx->DR = Data;
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_ReceiveData
+* Description : Returns the most recent received data by the SPIx/I2Sx peripheral.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - 2 or 3 in I2S mode
+* Output : None
+* Return : The value of the received data.
+*******************************************************************************/
+u16 SPI_I2S_ReceiveData(SPI_TypeDef* SPIx)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+
+ /* Return the data in the DR register */
+ return SPIx->DR;
+}
+
+/*******************************************************************************
+* Function Name : SPI_NSSInternalSoftwareConfig
+* Description : Configures internally by software the NSS pin for the selected
+* SPI.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - SPI_NSSInternalSoft: specifies the SPI NSS internal state.
+* This parameter can be one of the following values:
+* - SPI_NSSInternalSoft_Set: Set NSS pin internally
+* - SPI_NSSInternalSoft_Reset: Reset NSS pin internally
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, u16 SPI_NSSInternalSoft)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_NSS_INTERNAL(SPI_NSSInternalSoft));
+
+ if (SPI_NSSInternalSoft != SPI_NSSInternalSoft_Reset)
+ {
+ /* Set NSS pin internally by software */
+ SPIx->CR1 |= SPI_NSSInternalSoft_Set;
+ }
+ else
+ {
+ /* Reset NSS pin internally by software */
+ SPIx->CR1 &= SPI_NSSInternalSoft_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_SSOutputCmd
+* Description : Enables or disables the SS output for the selected SPI.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - NewState: new state of the SPIx SS output.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected SPI SS output */
+ SPIx->CR2 |= CR2_SSOE_Set;
+ }
+ else
+ {
+ /* Disable the selected SPI SS output */
+ SPIx->CR2 &= CR2_SSOE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_DataSizeConfig
+* Description : Configures the data size for the selected SPI.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - SPI_DataSize: specifies the SPI data size.
+* This parameter can be one of the following values:
+* - SPI_DataSize_16b: Set data frame format to 16bit
+* - SPI_DataSize_8b: Set data frame format to 8bit
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_DataSizeConfig(SPI_TypeDef* SPIx, u16 SPI_DataSize)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_DATASIZE(SPI_DataSize));
+
+ /* Clear DFF bit */
+ SPIx->CR1 &= (u16)~SPI_DataSize_16b;
+ /* Set new DFF bit value */
+ SPIx->CR1 |= SPI_DataSize;
+}
+
+/*******************************************************************************
+* Function Name : SPI_TransmitCRC
+* Description : Transmit the SPIx CRC value.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_TransmitCRC(SPI_TypeDef* SPIx)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+
+ /* Enable the selected SPI CRC transmission */
+ SPIx->CR1 |= CR1_CRCNext_Set;
+}
+
+/*******************************************************************************
+* Function Name : SPI_CalculateCRC
+* Description : Enables or disables the CRC value calculation of the
+* transfered bytes.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - NewState: new state of the SPIx CRC value calculation.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected SPI CRC calculation */
+ SPIx->CR1 |= CR1_CRCEN_Set;
+ }
+ else
+ {
+ /* Disable the selected SPI CRC calculation */
+ SPIx->CR1 &= CR1_CRCEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_GetCRC
+* Description : Returns the transmit or the receive CRC register value for
+* the specified SPI.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - SPI_CRC: specifies the CRC register to be read.
+* This parameter can be one of the following values:
+* - SPI_CRC_Tx: Selects Tx CRC register
+* - SPI_CRC_Rx: Selects Rx CRC register
+* Output : None
+* Return : The selected CRC register value..
+*******************************************************************************/
+u16 SPI_GetCRC(SPI_TypeDef* SPIx, u8 SPI_CRC)
+{
+ u16 crcreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_CRC(SPI_CRC));
+
+ if (SPI_CRC != SPI_CRC_Rx)
+ {
+ /* Get the Tx CRC register */
+ crcreg = SPIx->TXCRCR;
+ }
+ else
+ {
+ /* Get the Rx CRC register */
+ crcreg = SPIx->RXCRCR;
+ }
+
+ /* Return the selected CRC register */
+ return crcreg;
+}
+
+/*******************************************************************************
+* Function Name : SPI_GetCRCPolynomial
+* Description : Returns the CRC Polynomial register value for the specified SPI.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* Output : None
+* Return : The CRC Polynomial register value.
+*******************************************************************************/
+u16 SPI_GetCRCPolynomial(SPI_TypeDef* SPIx)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+
+ /* Return the CRC polynomial register */
+ return SPIx->CRCPR;
+}
+
+/*******************************************************************************
+* Function Name : SPI_BiDirectionalLineConfig
+* Description : Selects the data transfer direction in bi-directional mode
+* for the specified SPI.
+* Input : - SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+* - SPI_Direction: specifies the data transfer direction in
+* bi-directional mode.
+* This parameter can be one of the following values:
+* - SPI_Direction_Tx: Selects Tx transmission direction
+* - SPI_Direction_Rx: Selects Rx receive direction
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, u16 SPI_Direction)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_DIRECTION(SPI_Direction));
+
+ if (SPI_Direction == SPI_Direction_Tx)
+ {
+ /* Set the Tx only mode */
+ SPIx->CR1 |= SPI_Direction_Tx;
+ }
+ else
+ {
+ /* Set the Rx only mode */
+ SPIx->CR1 &= SPI_Direction_Rx;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_GetFlagStatus
+* Description : Checks whether the specified SPI/I2S flag is set or not.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - 2 or 3 in I2S mode
+* - SPI_I2S_FLAG: specifies the SPI/I2S flag to check.
+* This parameter can be one of the following values:
+* - SPI_I2S_FLAG_TXE: Transmit buffer empty flag.
+* - SPI_I2S_FLAG_RXNE: Receive buffer not empty flag.
+* - SPI_I2S_FLAG_BSY: Busy flag.
+* - SPI_I2S_FLAG_OVR: Overrun flag.
+* - SPI_FLAG_MODF: Mode Fault flag.
+* - SPI_FLAG_CRCERR: CRC Error flag.
+* - I2S_FLAG_UDR: Underrun Error flag.
+* - I2S_FLAG_CHSIDE: Channel Side flag.
+* Output : None
+* Return : The new state of SPI_I2S_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, u16 SPI_I2S_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_I2S_GET_FLAG(SPI_I2S_FLAG));
+
+ /* Check the status of the specified SPI/I2S flag */
+ if ((SPIx->SR & SPI_I2S_FLAG) != (u16)RESET)
+ {
+ /* SPI_I2S_FLAG is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* SPI_I2S_FLAG is reset */
+ bitstatus = RESET;
+ }
+ /* Return the SPI_I2S_FLAG status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_ClearFlag
+* Description : Clears the SPIx CRC Error (CRCERR) flag.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - SPI_I2S_FLAG: specifies the SPI flag to clear.
+* This function clears only CRCERR flag.
+* Notes:
+* - OVR (OverRun error) flag is cleared by software
+* sequence: a read operation to SPI_DR register
+* (SPI_I2S_ReceiveData()) followed by a read operation
+* to SPI_SR register (SPI_I2S_GetFlagStatus()).
+* - UDR (UnderRun error) flag is cleared by a read
+* operation to SPI_SR register (SPI_I2S_GetFlagStatus()).
+* - MODF (Mode Fault) flag is cleared by software sequence:
+* a read/write operation to SPI_SR register
+* (SPI_I2S_GetFlagStatus()) followed by a write
+* operation to SPI_CR1 register (SPI_Cmd() to enable
+* the SPI).
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, u16 SPI_I2S_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_I2S_CLEAR_FLAG(SPI_I2S_FLAG));
+
+ /* Clear the selected SPI CRC Error (CRCERR) flag */
+ SPIx->SR = (u16)~SPI_I2S_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_GetITStatus
+* Description : Checks whether the specified SPI/I2S interrupt has occurred or not.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - 2 or 3 in I2S mode
+* - SPI_I2S_IT: specifies the SPI/I2S interrupt source to check.
+* This parameter can be one of the following values:
+* - SPI_I2S_IT_TXE: Transmit buffer empty interrupt.
+* - SPI_I2S_IT_RXNE: Receive buffer not empty interrupt.
+* - SPI_I2S_IT_OVR: Overrun interrupt.
+* - SPI_IT_MODF: Mode Fault interrupt.
+* - SPI_IT_CRCERR: CRC Error interrupt.
+* - I2S_IT_UDR: Underrun Error interrupt.
+* Output : None
+* Return : The new state of SPI_I2S_IT (SET or RESET).
+*******************************************************************************/
+ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, u8 SPI_I2S_IT)
+{
+ ITStatus bitstatus = RESET;
+ u16 itpos = 0, itmask = 0, enablestatus = 0;
+
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_I2S_GET_IT(SPI_I2S_IT));
+
+ /* Get the SPI/I2S IT index */
+ itpos = (u16)((u16)0x01 << (SPI_I2S_IT & (u8)0x0F));
+
+ /* Get the SPI/I2S IT mask */
+ itmask = SPI_I2S_IT >> 4;
+ /* Set the IT mask */
+ itmask = (u16)((u16)0x01 << itmask);
+ /* Get the SPI_I2S_IT enable bit status */
+ enablestatus = (SPIx->CR2 & itmask) ;
+
+ /* Check the status of the specified SPI/I2S interrupt */
+ if (((SPIx->SR & itpos) != (u16)RESET) && enablestatus)
+ {
+ /* SPI_I2S_IT is set */
+ bitstatus = SET;
+ }
+ else
+ {
+ /* SPI_I2S_IT is reset */
+ bitstatus = RESET;
+ }
+ /* Return the SPI_I2S_IT status */
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : SPI_I2S_ClearITPendingBit
+* Description : Clears the SPIx CRC Error (CRCERR) interrupt pending bit.
+* Input : - SPIx: where x can be :
+* - 1, 2 or 3 in SPI mode
+* - SPI_I2S_IT: specifies the SPI interrupt pending bit to clear.
+* This function clears only CRCERR intetrrupt pending bit.
+* Notes:
+* - OVR (OverRun Error) interrupt pending bit is cleared
+* by software sequence: a read operation to SPI_DR
+* register (SPI_I2S_ReceiveData()) followed by a read
+* operation to SPI_SR register (SPI_I2S_GetITStatus()).
+* - UDR (UnderRun Error) interrupt pending bit is cleared
+* by a read operation to SPI_SR register
+* (SPI_I2S_GetITStatus()).
+* - MODF (Mode Fault) interrupt pending bit is cleared by
+* software sequence: a read/write operation to SPI_SR
+* register (SPI_I2S_GetITStatus()) followed by a write
+* operation to SPI_CR1 register (SPI_Cmd() to enable the
+* SPI).
+* Output : None
+* Return : None
+*******************************************************************************/
+void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, u8 SPI_I2S_IT)
+{
+ u16 itpos = 0;
+
+ /* Check the parameters */
+ assert_param(IS_SPI_ALL_PERIPH(SPIx));
+ assert_param(IS_SPI_I2S_CLEAR_IT(SPI_I2S_IT));
+
+ /* Get the SPI IT index */
+ itpos = (u16)((u16)0x01 << (SPI_I2S_IT & (u8)0x0F));
+ /* Clear the selected SPI CRC Error (CRCERR) interrupt pending bit */
+ SPIx->SR = (u16)~itpos;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_systick.c b/src/stm32lib/src/stm32f10x_systick.c new file mode 100644 index 0000000..53deb76 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_systick.c @@ -0,0 +1,181 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_systick.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the SysTick firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_systick.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ---------------------- SysTick registers bit mask -------------------- */
+/* CTRL TICKINT Mask */
+#define CTRL_TICKINT_Set ((u32)0x00000002)
+#define CTRL_TICKINT_Reset ((u32)0xFFFFFFFD)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : SysTick_CLKSourceConfig
+* Description : Configures the SysTick clock source.
+* Input : - SysTick_CLKSource: specifies the SysTick clock source.
+* This parameter can be one of the following values:
+* - SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8
+* selected as SysTick clock source.
+* - SysTick_CLKSource_HCLK: AHB clock selected as
+* SysTick clock source.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTick_CLKSourceConfig(u32 SysTick_CLKSource)
+{
+ /* Check the parameters */
+ assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource));
+
+ if (SysTick_CLKSource == SysTick_CLKSource_HCLK)
+ {
+ SysTick->CTRL |= SysTick_CLKSource_HCLK;
+ }
+ else
+ {
+ SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SysTick_SetReload
+* Description : Sets SysTick Reload value.
+* Input : - Reload: SysTick Reload new value.
+* This parameter must be a number between 1 and 0xFFFFFF.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTick_SetReload(u32 Reload)
+{
+ /* Check the parameters */
+ assert_param(IS_SYSTICK_RELOAD(Reload));
+
+ SysTick->LOAD = Reload;
+}
+
+/*******************************************************************************
+* Function Name : SysTick_CounterCmd
+* Description : Enables or disables the SysTick counter.
+* Input : - SysTick_Counter: new state of the SysTick counter.
+* This parameter can be one of the following values:
+* - SysTick_Counter_Disable: Disable counter
+* - SysTick_Counter_Enable: Enable counter
+* - SysTick_Counter_Clear: Clear counter value to 0
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTick_CounterCmd(u32 SysTick_Counter)
+{
+ /* Check the parameters */
+ assert_param(IS_SYSTICK_COUNTER(SysTick_Counter));
+
+ if (SysTick_Counter == SysTick_Counter_Enable)
+ {
+ SysTick->CTRL |= SysTick_Counter_Enable;
+ }
+ else if (SysTick_Counter == SysTick_Counter_Disable)
+ {
+ SysTick->CTRL &= SysTick_Counter_Disable;
+ }
+ else /* SysTick_Counter == SysTick_Counter_Clear */
+ {
+ SysTick->VAL = SysTick_Counter_Clear;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SysTick_ITConfig
+* Description : Enables or disables the SysTick Interrupt.
+* Input : - NewState: new state of the SysTick Interrupt.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void SysTick_ITConfig(FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ SysTick->CTRL |= CTRL_TICKINT_Set;
+ }
+ else
+ {
+ SysTick->CTRL &= CTRL_TICKINT_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : SysTick_GetCounter
+* Description : Gets SysTick counter value.
+* Input : None
+* Output : None
+* Return : SysTick current value
+*******************************************************************************/
+u32 SysTick_GetCounter(void)
+{
+ return(SysTick->VAL);
+}
+
+/*******************************************************************************
+* Function Name : SysTick_GetFlagStatus
+* Description : Checks whether the specified SysTick flag is set or not.
+* Input : - SysTick_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - SysTick_FLAG_COUNT
+* - SysTick_FLAG_SKEW
+* - SysTick_FLAG_NOREF
+* Output : None
+* Return : None
+*******************************************************************************/
+FlagStatus SysTick_GetFlagStatus(u8 SysTick_FLAG)
+{
+ u32 statusreg = 0, tmp = 0 ;
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_SYSTICK_FLAG(SysTick_FLAG));
+
+ /* Get the SysTick register index */
+ tmp = SysTick_FLAG >> 3;
+
+ if (tmp == 2) /* The flag to check is in CTRL register */
+ {
+ statusreg = SysTick->CTRL;
+ }
+ else /* The flag to check is in CALIB register */
+ {
+ statusreg = SysTick->CALIB;
+ }
+
+ if ((statusreg & ((u32)1 << SysTick_FLAG)) != (u32)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_systick.lst b/src/stm32lib/src/stm32f10x_systick.lst new file mode 100644 index 0000000..c273c9a --- /dev/null +++ b/src/stm32lib/src/stm32f10x_systick.lst @@ -0,0 +1,403 @@ + 1 .syntax unified + 2 .cpu cortex-m3 + 3 .fpu softvfp + 4 .eabi_attribute 20, 1 + 5 .eabi_attribute 21, 1 + 6 .eabi_attribute 23, 3 + 7 .eabi_attribute 24, 1 + 8 .eabi_attribute 25, 1 + 9 .eabi_attribute 26, 1 + 10 .eabi_attribute 30, 4 + 11 .eabi_attribute 18, 4 + 12 .thumb + 13 .file "stm32f10x_systick.c" + 21 .Ltext0: + 22 .align 2 + 23 .global SysTick_CLKSourceConfig + 24 .thumb + 25 .thumb_func + 27 SysTick_CLKSourceConfig: + 28 .LFB23: + 29 .file 1 "stm32lib/src/stm32f10x_systick.c" + 1:stm32lib/src/stm32f10x_systick.c **** /******************** (C) COPYRIGHT 2008 STMicroelectronics ******************** + 2:stm32lib/src/stm32f10x_systick.c **** * File Name : stm32f10x_systick.c + 3:stm32lib/src/stm32f10x_systick.c **** * Author : MCD Application Team + 4:stm32lib/src/stm32f10x_systick.c **** * Version : V2.0.2 + 5:stm32lib/src/stm32f10x_systick.c **** * Date : 07/11/2008 + 6:stm32lib/src/stm32f10x_systick.c **** * Description : This file provides all the SysTick firmware functions. + 7:stm32lib/src/stm32f10x_systick.c **** ******************************************************************************** + 8:stm32lib/src/stm32f10x_systick.c **** * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + 9:stm32lib/src/stm32f10x_systick.c **** * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. + 10:stm32lib/src/stm32f10x_systick.c **** * AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, + 11:stm32lib/src/stm32f10x_systick.c **** * INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE + 12:stm32lib/src/stm32f10x_systick.c **** * CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING + 13:stm32lib/src/stm32f10x_systick.c **** * INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + 14:stm32lib/src/stm32f10x_systick.c **** *******************************************************************************/ + 15:stm32lib/src/stm32f10x_systick.c **** + 16:stm32lib/src/stm32f10x_systick.c **** /* Includes ------------------------------------------------------------------*/ + 17:stm32lib/src/stm32f10x_systick.c **** #include "stm32f10x_systick.h" + 18:stm32lib/src/stm32f10x_systick.c **** + 19:stm32lib/src/stm32f10x_systick.c **** /* Private typedef -----------------------------------------------------------*/ + 20:stm32lib/src/stm32f10x_systick.c **** /* Private define ------------------------------------------------------------*/ + 21:stm32lib/src/stm32f10x_systick.c **** /* ---------------------- SysTick registers bit mask -------------------- */ + 22:stm32lib/src/stm32f10x_systick.c **** /* CTRL TICKINT Mask */ + 23:stm32lib/src/stm32f10x_systick.c **** #define CTRL_TICKINT_Set ((u32)0x00000002) + 24:stm32lib/src/stm32f10x_systick.c **** #define CTRL_TICKINT_Reset ((u32)0xFFFFFFFD) + 25:stm32lib/src/stm32f10x_systick.c **** + 26:stm32lib/src/stm32f10x_systick.c **** /* Private macro -------------------------------------------------------------*/ + 27:stm32lib/src/stm32f10x_systick.c **** /* Private variables ---------------------------------------------------------*/ + 28:stm32lib/src/stm32f10x_systick.c **** /* Private function prototypes -----------------------------------------------*/ + 29:stm32lib/src/stm32f10x_systick.c **** /* Private functions ---------------------------------------------------------*/ + 30:stm32lib/src/stm32f10x_systick.c **** + 31:stm32lib/src/stm32f10x_systick.c **** /******************************************************************************* + 32:stm32lib/src/stm32f10x_systick.c **** * Function Name : SysTick_CLKSourceConfig + 33:stm32lib/src/stm32f10x_systick.c **** * Description : Configures the SysTick clock source. + 34:stm32lib/src/stm32f10x_systick.c **** * Input : - SysTick_CLKSource: specifies the SysTick clock source. + 35:stm32lib/src/stm32f10x_systick.c **** * This parameter can be one of the following values: + 36:stm32lib/src/stm32f10x_systick.c **** * - SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8 + 37:stm32lib/src/stm32f10x_systick.c **** * selected as SysTick clock source. + 38:stm32lib/src/stm32f10x_systick.c **** * - SysTick_CLKSource_HCLK: AHB clock selected as + 39:stm32lib/src/stm32f10x_systick.c **** * SysTick clock source. + 40:stm32lib/src/stm32f10x_systick.c **** * Output : None + 41:stm32lib/src/stm32f10x_systick.c **** * Return : None + 42:stm32lib/src/stm32f10x_systick.c **** *******************************************************************************/ + 43:stm32lib/src/stm32f10x_systick.c **** void SysTick_CLKSourceConfig(u32 SysTick_CLKSource) + 44:stm32lib/src/stm32f10x_systick.c **** { + 30 .loc 1 44 0 + 31 @ args = 0, pretend = 0, frame = 0 + 32 @ frame_needed = 0, uses_anonymous_args = 0 + 33 @ link register save eliminated. + 34 .LVL0: + 45:stm32lib/src/stm32f10x_systick.c **** /* Check the parameters */ + 46:stm32lib/src/stm32f10x_systick.c **** assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource)); + 47:stm32lib/src/stm32f10x_systick.c **** + 48:stm32lib/src/stm32f10x_systick.c **** if (SysTick_CLKSource == SysTick_CLKSource_HCLK) + 35 .loc 1 48 0 + 36 0000 0428 cmp r0, #4 + 37 0002 04D1 bne .L2 + 49:stm32lib/src/stm32f10x_systick.c **** { + 50:stm32lib/src/stm32f10x_systick.c **** SysTick->CTRL |= SysTick_CLKSource_HCLK; + 38 .loc 1 50 0 + 39 0004 054A ldr r2, .L6 + 40 0006 1368 ldr r3, [r2, #0] + 41 0008 43F00403 orr r3, r3, #4 + 42 000c 03E0 b .L5 + 43 .L2: + 51:stm32lib/src/stm32f10x_systick.c **** } + 52:stm32lib/src/stm32f10x_systick.c **** else + 53:stm32lib/src/stm32f10x_systick.c **** { + 54:stm32lib/src/stm32f10x_systick.c **** SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8; + 44 .loc 1 54 0 + 45 000e 034A ldr r2, .L6 + 46 0010 1368 ldr r3, [r2, #0] + 47 0012 23F00403 bic r3, r3, #4 + 48 .L5: + 49 0016 1360 str r3, [r2, #0] + 55:stm32lib/src/stm32f10x_systick.c **** } + 56:stm32lib/src/stm32f10x_systick.c **** } + 50 .loc 1 56 0 + 51 0018 7047 bx lr + 52 .L7: + 53 001a 00BF .align 2 + 54 .L6: + 55 001c 10E000E0 .word -536813552 + 56 .LFE23: + 58 .align 2 + 59 .global SysTick_SetReload + 60 .thumb + 61 .thumb_func + 63 SysTick_SetReload: + 64 .LFB24: + 57:stm32lib/src/stm32f10x_systick.c **** + 58:stm32lib/src/stm32f10x_systick.c **** /******************************************************************************* + 59:stm32lib/src/stm32f10x_systick.c **** * Function Name : SysTick_SetReload + 60:stm32lib/src/stm32f10x_systick.c **** * Description : Sets SysTick Reload value. + 61:stm32lib/src/stm32f10x_systick.c **** * Input : - Reload: SysTick Reload new value. + 62:stm32lib/src/stm32f10x_systick.c **** * This parameter must be a number between 1 and 0xFFFFFF. + 63:stm32lib/src/stm32f10x_systick.c **** * Output : None + 64:stm32lib/src/stm32f10x_systick.c **** * Return : None + 65:stm32lib/src/stm32f10x_systick.c **** *******************************************************************************/ + 66:stm32lib/src/stm32f10x_systick.c **** void SysTick_SetReload(u32 Reload) + 67:stm32lib/src/stm32f10x_systick.c **** { + 65 .loc 1 67 0 + 66 @ args = 0, pretend = 0, frame = 0 + 67 @ frame_needed = 0, uses_anonymous_args = 0 + 68 @ link register save eliminated. + 69 .LVL1: + 68:stm32lib/src/stm32f10x_systick.c **** /* Check the parameters */ + 69:stm32lib/src/stm32f10x_systick.c **** assert_param(IS_SYSTICK_RELOAD(Reload)); + 70:stm32lib/src/stm32f10x_systick.c **** + 71:stm32lib/src/stm32f10x_systick.c **** SysTick->LOAD = Reload; + 70 .loc 1 71 0 + 71 0020 014B ldr r3, .L10 + 72 0022 5860 str r0, [r3, #4] + 72:stm32lib/src/stm32f10x_systick.c **** } + 73 .loc 1 72 0 + 74 0024 7047 bx lr + 75 .L11: + 76 0026 00BF .align 2 + 77 .L10: + 78 0028 10E000E0 .word -536813552 + 79 .LFE24: + 81 .align 2 + 82 .global SysTick_CounterCmd + 83 .thumb + 84 .thumb_func + 86 SysTick_CounterCmd: + 87 .LFB25: + 73:stm32lib/src/stm32f10x_systick.c **** + 74:stm32lib/src/stm32f10x_systick.c **** /******************************************************************************* + 75:stm32lib/src/stm32f10x_systick.c **** * Function Name : SysTick_CounterCmd + 76:stm32lib/src/stm32f10x_systick.c **** * Description : Enables or disables the SysTick counter. + 77:stm32lib/src/stm32f10x_systick.c **** * Input : - SysTick_Counter: new state of the SysTick counter. + 78:stm32lib/src/stm32f10x_systick.c **** * This parameter can be one of the following values: + 79:stm32lib/src/stm32f10x_systick.c **** * - SysTick_Counter_Disable: Disable counter + 80:stm32lib/src/stm32f10x_systick.c **** * - SysTick_Counter_Enable: Enable counter + 81:stm32lib/src/stm32f10x_systick.c **** * - SysTick_Counter_Clear: Clear counter value to 0 + 82:stm32lib/src/stm32f10x_systick.c **** * Output : None + 83:stm32lib/src/stm32f10x_systick.c **** * Return : None + 84:stm32lib/src/stm32f10x_systick.c **** *******************************************************************************/ + 85:stm32lib/src/stm32f10x_systick.c **** void SysTick_CounterCmd(u32 SysTick_Counter) + 86:stm32lib/src/stm32f10x_systick.c **** { + 88 .loc 1 86 0 + 89 @ args = 0, pretend = 0, frame = 0 + 90 @ frame_needed = 0, uses_anonymous_args = 0 + 91 @ link register save eliminated. + 92 .LVL2: + 87:stm32lib/src/stm32f10x_systick.c **** /* Check the parameters */ + 88:stm32lib/src/stm32f10x_systick.c **** assert_param(IS_SYSTICK_COUNTER(SysTick_Counter)); + 89:stm32lib/src/stm32f10x_systick.c **** + 90:stm32lib/src/stm32f10x_systick.c **** if (SysTick_Counter == SysTick_Counter_Enable) + 93 .loc 1 90 0 + 94 002c 0128 cmp r0, #1 + 95 002e 04D1 bne .L13 + 91:stm32lib/src/stm32f10x_systick.c **** { + 92:stm32lib/src/stm32f10x_systick.c **** SysTick->CTRL |= SysTick_Counter_Enable; + 96 .loc 1 92 0 + 97 0030 084A ldr r2, .L18 + 98 0032 1368 ldr r3, [r2, #0] + 99 0034 43F00103 orr r3, r3, #1 + 100 0038 06E0 b .L17 + 101 .L13: + 93:stm32lib/src/stm32f10x_systick.c **** } + 94:stm32lib/src/stm32f10x_systick.c **** else if (SysTick_Counter == SysTick_Counter_Disable) + 102 .loc 1 94 0 + 103 003a 10F1020F cmn r0, #2 + 104 003e 05D1 bne .L15 + 95:stm32lib/src/stm32f10x_systick.c **** { + 96:stm32lib/src/stm32f10x_systick.c **** SysTick->CTRL &= SysTick_Counter_Disable; + 105 .loc 1 96 0 + 106 0040 044A ldr r2, .L18 + 107 0042 1368 ldr r3, [r2, #0] + 108 0044 23F00103 bic r3, r3, #1 + 109 .L17: + 110 0048 1360 str r3, [r2, #0] + 111 004a 02E0 b .L16 + 112 .L15: + 97:stm32lib/src/stm32f10x_systick.c **** } + 98:stm32lib/src/stm32f10x_systick.c **** else /* SysTick_Counter == SysTick_Counter_Clear */ + 99:stm32lib/src/stm32f10x_systick.c **** { + 100:stm32lib/src/stm32f10x_systick.c **** SysTick->VAL = SysTick_Counter_Clear; + 113 .loc 1 100 0 + 114 004c 014B ldr r3, .L18 + 115 004e 0022 movs r2, #0 + 116 0050 9A60 str r2, [r3, #8] + 117 .L16: + 101:stm32lib/src/stm32f10x_systick.c **** } + 102:stm32lib/src/stm32f10x_systick.c **** } + 118 .loc 1 102 0 + 119 0052 7047 bx lr + 120 .L19: + 121 .align 2 + 122 .L18: + 123 0054 10E000E0 .word -536813552 + 124 .LFE25: + 126 .align 2 + 127 .global SysTick_ITConfig + 128 .thumb + 129 .thumb_func + 131 SysTick_ITConfig: + 132 .LFB26: + 103:stm32lib/src/stm32f10x_systick.c **** + 104:stm32lib/src/stm32f10x_systick.c **** /******************************************************************************* + 105:stm32lib/src/stm32f10x_systick.c **** * Function Name : SysTick_ITConfig + 106:stm32lib/src/stm32f10x_systick.c **** * Description : Enables or disables the SysTick Interrupt. + 107:stm32lib/src/stm32f10x_systick.c **** * Input : - NewState: new state of the SysTick Interrupt. + 108:stm32lib/src/stm32f10x_systick.c **** * This parameter can be: ENABLE or DISABLE. + 109:stm32lib/src/stm32f10x_systick.c **** * Output : None + 110:stm32lib/src/stm32f10x_systick.c **** * Return : None + 111:stm32lib/src/stm32f10x_systick.c **** *******************************************************************************/ + 112:stm32lib/src/stm32f10x_systick.c **** void SysTick_ITConfig(FunctionalState NewState) + 113:stm32lib/src/stm32f10x_systick.c **** { + 133 .loc 1 113 0 + 134 @ args = 0, pretend = 0, frame = 0 + 135 @ frame_needed = 0, uses_anonymous_args = 0 + 136 @ link register save eliminated. + 137 .LVL3: + 114:stm32lib/src/stm32f10x_systick.c **** /* Check the parameters */ + 115:stm32lib/src/stm32f10x_systick.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 116:stm32lib/src/stm32f10x_systick.c **** + 117:stm32lib/src/stm32f10x_systick.c **** if (NewState != DISABLE) + 138 .loc 1 117 0 + 139 0058 20B1 cbz r0, .L21 + 118:stm32lib/src/stm32f10x_systick.c **** { + 119:stm32lib/src/stm32f10x_systick.c **** SysTick->CTRL |= CTRL_TICKINT_Set; + 140 .loc 1 119 0 + 141 005a 054A ldr r2, .L25 + 142 005c 1368 ldr r3, [r2, #0] + 143 005e 43F00203 orr r3, r3, #2 + 144 0062 03E0 b .L24 + 145 .L21: + 120:stm32lib/src/stm32f10x_systick.c **** } + 121:stm32lib/src/stm32f10x_systick.c **** else + 122:stm32lib/src/stm32f10x_systick.c **** { + 123:stm32lib/src/stm32f10x_systick.c **** SysTick->CTRL &= CTRL_TICKINT_Reset; + 146 .loc 1 123 0 + 147 0064 024A ldr r2, .L25 + 148 0066 1368 ldr r3, [r2, #0] + 149 0068 23F00203 bic r3, r3, #2 + 150 .L24: + 151 006c 1360 str r3, [r2, #0] + 124:stm32lib/src/stm32f10x_systick.c **** } + 125:stm32lib/src/stm32f10x_systick.c **** } + 152 .loc 1 125 0 + 153 006e 7047 bx lr + 154 .L26: + 155 .align 2 + 156 .L25: + 157 0070 10E000E0 .word -536813552 + 158 .LFE26: + 160 .align 2 + 161 .global SysTick_GetCounter + 162 .thumb + 163 .thumb_func + 165 SysTick_GetCounter: + 166 .LFB27: + 126:stm32lib/src/stm32f10x_systick.c **** + 127:stm32lib/src/stm32f10x_systick.c **** /******************************************************************************* + 128:stm32lib/src/stm32f10x_systick.c **** * Function Name : SysTick_GetCounter + 129:stm32lib/src/stm32f10x_systick.c **** * Description : Gets SysTick counter value. + 130:stm32lib/src/stm32f10x_systick.c **** * Input : None + 131:stm32lib/src/stm32f10x_systick.c **** * Output : None + 132:stm32lib/src/stm32f10x_systick.c **** * Return : SysTick current value + 133:stm32lib/src/stm32f10x_systick.c **** *******************************************************************************/ + 134:stm32lib/src/stm32f10x_systick.c **** u32 SysTick_GetCounter(void) + 135:stm32lib/src/stm32f10x_systick.c **** { + 167 .loc 1 135 0 + 168 @ args = 0, pretend = 0, frame = 0 + 169 @ frame_needed = 0, uses_anonymous_args = 0 + 170 @ link register save eliminated. + 136:stm32lib/src/stm32f10x_systick.c **** return(SysTick->VAL); + 171 .loc 1 136 0 + 172 0074 014B ldr r3, .L29 + 173 0076 9868 ldr r0, [r3, #8] + 137:stm32lib/src/stm32f10x_systick.c **** } + 174 .loc 1 137 0 + 175 0078 7047 bx lr + 176 .L30: + 177 007a 00BF .align 2 + 178 .L29: + 179 007c 10E000E0 .word -536813552 + 180 .LFE27: + 182 .align 2 + 183 .global SysTick_GetFlagStatus + 184 .thumb + 185 .thumb_func + 187 SysTick_GetFlagStatus: + 188 .LFB28: + 138:stm32lib/src/stm32f10x_systick.c **** + 139:stm32lib/src/stm32f10x_systick.c **** /******************************************************************************* + 140:stm32lib/src/stm32f10x_systick.c **** * Function Name : SysTick_GetFlagStatus + 141:stm32lib/src/stm32f10x_systick.c **** * Description : Checks whether the specified SysTick flag is set or not. + 142:stm32lib/src/stm32f10x_systick.c **** * Input : - SysTick_FLAG: specifies the flag to check. + 143:stm32lib/src/stm32f10x_systick.c **** * This parameter can be one of the following values: + 144:stm32lib/src/stm32f10x_systick.c **** * - SysTick_FLAG_COUNT + 145:stm32lib/src/stm32f10x_systick.c **** * - SysTick_FLAG_SKEW + 146:stm32lib/src/stm32f10x_systick.c **** * - SysTick_FLAG_NOREF + 147:stm32lib/src/stm32f10x_systick.c **** * Output : None + 148:stm32lib/src/stm32f10x_systick.c **** * Return : None + 149:stm32lib/src/stm32f10x_systick.c **** *******************************************************************************/ + 150:stm32lib/src/stm32f10x_systick.c **** FlagStatus SysTick_GetFlagStatus(u8 SysTick_FLAG) + 151:stm32lib/src/stm32f10x_systick.c **** { + 189 .loc 1 151 0 + 190 @ args = 0, pretend = 0, frame = 0 + 191 @ frame_needed = 0, uses_anonymous_args = 0 + 192 @ link register save eliminated. + 193 .LVL4: + 152:stm32lib/src/stm32f10x_systick.c **** u32 statusreg = 0, tmp = 0 ; + 153:stm32lib/src/stm32f10x_systick.c **** FlagStatus bitstatus = RESET; + 154:stm32lib/src/stm32f10x_systick.c **** + 155:stm32lib/src/stm32f10x_systick.c **** /* Check the parameters */ + 156:stm32lib/src/stm32f10x_systick.c **** assert_param(IS_SYSTICK_FLAG(SysTick_FLAG)); + 157:stm32lib/src/stm32f10x_systick.c **** + 158:stm32lib/src/stm32f10x_systick.c **** /* Get the SysTick register index */ + 159:stm32lib/src/stm32f10x_systick.c **** tmp = SysTick_FLAG >> 3; + 160:stm32lib/src/stm32f10x_systick.c **** + 161:stm32lib/src/stm32f10x_systick.c **** if (tmp == 2) /* The flag to check is in CTRL register */ + 194 .loc 1 161 0 + 195 0080 C308 lsrs r3, r0, #3 + 196 0082 022B cmp r3, #2 + 162:stm32lib/src/stm32f10x_systick.c **** { + 163:stm32lib/src/stm32f10x_systick.c **** statusreg = SysTick->CTRL; + 197 .loc 1 163 0 + 198 0084 0CBF ite eq + 199 0086 054B ldreq r3, .L35 + 164:stm32lib/src/stm32f10x_systick.c **** } + 165:stm32lib/src/stm32f10x_systick.c **** else /* The flag to check is in CALIB register */ + 166:stm32lib/src/stm32f10x_systick.c **** { + 167:stm32lib/src/stm32f10x_systick.c **** statusreg = SysTick->CALIB; + 200 .loc 1 167 0 + 201 0088 044B ldrne r3, .L35 + 202 .loc 1 151 0 + 203 008a 0246 mov r2, r0 + 204 .loc 1 163 0 + 205 008c 0CBF ite eq + 206 008e 1868 ldreq r0, [r3, #0] + 207 .LVL5: + 208 .loc 1 167 0 + 209 0090 D868 ldrne r0, [r3, #12] + 210 0092 D040 lsrs r0, r0, r2 + 211 .LVL6: + 168:stm32lib/src/stm32f10x_systick.c **** } + 169:stm32lib/src/stm32f10x_systick.c **** + 170:stm32lib/src/stm32f10x_systick.c **** if ((statusreg & ((u32)1 << SysTick_FLAG)) != (u32)RESET) + 171:stm32lib/src/stm32f10x_systick.c **** { + 172:stm32lib/src/stm32f10x_systick.c **** bitstatus = SET; + 173:stm32lib/src/stm32f10x_systick.c **** } + 174:stm32lib/src/stm32f10x_systick.c **** else + 175:stm32lib/src/stm32f10x_systick.c **** { + 176:stm32lib/src/stm32f10x_systick.c **** bitstatus = RESET; + 177:stm32lib/src/stm32f10x_systick.c **** } + 178:stm32lib/src/stm32f10x_systick.c **** return bitstatus; + 179:stm32lib/src/stm32f10x_systick.c **** } + 212 .loc 1 179 0 + 213 0094 00F00100 and r0, r0, #1 + 214 0098 7047 bx lr + 215 .L36: + 216 009a 00BF .align 2 + 217 .L35: + 218 009c 10E000E0 .word -536813552 + 219 .LFE28: + 285 .Letext0: +DEFINED SYMBOLS + *ABS*:00000000 stm32f10x_systick.c + /tmp/ccXtJJZP.s:22 .text:00000000 $t + /tmp/ccXtJJZP.s:27 .text:00000000 SysTick_CLKSourceConfig + /tmp/ccXtJJZP.s:55 .text:0000001c $d + /tmp/ccXtJJZP.s:58 .text:00000020 $t + /tmp/ccXtJJZP.s:63 .text:00000020 SysTick_SetReload + /tmp/ccXtJJZP.s:78 .text:00000028 $d + /tmp/ccXtJJZP.s:81 .text:0000002c $t + /tmp/ccXtJJZP.s:86 .text:0000002c SysTick_CounterCmd + /tmp/ccXtJJZP.s:123 .text:00000054 $d + /tmp/ccXtJJZP.s:126 .text:00000058 $t + /tmp/ccXtJJZP.s:131 .text:00000058 SysTick_ITConfig + /tmp/ccXtJJZP.s:157 .text:00000070 $d + /tmp/ccXtJJZP.s:160 .text:00000074 $t + /tmp/ccXtJJZP.s:165 .text:00000074 SysTick_GetCounter + /tmp/ccXtJJZP.s:179 .text:0000007c $d + /tmp/ccXtJJZP.s:182 .text:00000080 $t + /tmp/ccXtJJZP.s:187 .text:00000080 SysTick_GetFlagStatus + /tmp/ccXtJJZP.s:218 .text:0000009c $d + +NO UNDEFINED SYMBOLS diff --git a/src/stm32lib/src/stm32f10x_tim.c b/src/stm32lib/src/stm32f10x_tim.c new file mode 100644 index 0000000..ca971e2 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_tim.c @@ -0,0 +1,3219 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_tim.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the TIM firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_tim.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ---------------------- TIM registers bit mask ------------------------ */
+#define CR1_CEN_Set ((u16)0x0001)
+#define CR1_CEN_Reset ((u16)0x03FE)
+#define CR1_UDIS_Set ((u16)0x0002)
+#define CR1_UDIS_Reset ((u16)0x03FD)
+#define CR1_URS_Set ((u16)0x0004)
+#define CR1_URS_Reset ((u16)0x03FB)
+#define CR1_OPM_Reset ((u16)0x03F7)
+#define CR1_CounterMode_Mask ((u16)0x038F)
+#define CR1_ARPE_Set ((u16)0x0080)
+#define CR1_ARPE_Reset ((u16)0x037F)
+#define CR1_CKD_Mask ((u16)0x00FF)
+
+#define CR2_CCPC_Set ((u16)0x0001)
+#define CR2_CCPC_Reset ((u16)0xFFFE)
+#define CR2_CCUS_Set ((u16)0x0004)
+#define CR2_CCUS_Reset ((u16)0xFFFB)
+#define CR2_CCDS_Set ((u16)0x0008)
+#define CR2_CCDS_Reset ((u16)0xFFF7)
+#define CR2_MMS_Mask ((u16)0xFF8F)
+#define CR2_TI1S_Set ((u16)0x0080)
+#define CR2_TI1S_Reset ((u16)0xFF7F)
+#define CR2_OIS1_Reset ((u16)0x7EFF)
+#define CR2_OIS1N_Reset ((u16)0x7DFF)
+#define CR2_OIS2_Reset ((u16)0x7BFF)
+#define CR2_OIS2N_Reset ((u16)0x77FF)
+#define CR2_OIS3_Reset ((u16)0x6FFF)
+#define CR2_OIS3N_Reset ((u16)0x5FFF)
+#define CR2_OIS4_Reset ((u16)0x3FFF)
+
+#define SMCR_SMS_Mask ((u16)0xFFF8)
+#define SMCR_ETR_Mask ((u16)0x00FF)
+#define SMCR_TS_Mask ((u16)0xFF8F)
+#define SMCR_MSM_Reset ((u16)0xFF7F)
+#define SMCR_ECE_Set ((u16)0x4000)
+
+#define CCMR_CC13S_Mask ((u16)0xFFFC)
+#define CCMR_CC24S_Mask ((u16)0xFCFF)
+#define CCMR_TI13Direct_Set ((u16)0x0001)
+#define CCMR_TI24Direct_Set ((u16)0x0100)
+#define CCMR_OC13FE_Reset ((u16)0xFFFB)
+#define CCMR_OC24FE_Reset ((u16)0xFBFF)
+#define CCMR_OC13PE_Reset ((u16)0xFFF7)
+#define CCMR_OC24PE_Reset ((u16)0xF7FF)
+#define CCMR_OC13M_Mask ((u16)0xFF8F)
+#define CCMR_OC24M_Mask ((u16)0x8FFF)
+
+#define CCMR_OC13CE_Reset ((u16)0xFF7F)
+#define CCMR_OC24CE_Reset ((u16)0x7FFF)
+
+#define CCMR_IC13PSC_Mask ((u16)0xFFF3)
+#define CCMR_IC24PSC_Mask ((u16)0xF3FF)
+#define CCMR_IC13F_Mask ((u16)0xFF0F)
+#define CCMR_IC24F_Mask ((u16)0x0FFF)
+
+#define CCMR_Offset ((u16)0x0018)
+#define CCER_CCE_Set ((u16)0x0001)
+#define CCER_CCNE_Set ((u16)0x0004)
+
+#define CCER_CC1P_Reset ((u16)0xFFFD)
+#define CCER_CC2P_Reset ((u16)0xFFDF)
+#define CCER_CC3P_Reset ((u16)0xFDFF)
+#define CCER_CC4P_Reset ((u16)0xDFFF)
+
+#define CCER_CC1NP_Reset ((u16)0xFFF7)
+#define CCER_CC2NP_Reset ((u16)0xFF7F)
+#define CCER_CC3NP_Reset ((u16)0xF7FF)
+
+#define CCER_CC1E_Set ((u16)0x0001)
+#define CCER_CC1E_Reset ((u16)0xFFFE)
+
+#define CCER_CC1NE_Reset ((u16)0xFFFB)
+
+#define CCER_CC2E_Set ((u16)0x0010)
+#define CCER_CC2E_Reset ((u16)0xFFEF)
+
+#define CCER_CC2NE_Reset ((u16)0xFFBF)
+
+#define CCER_CC3E_Set ((u16)0x0100)
+#define CCER_CC3E_Reset ((u16)0xFEFF)
+
+#define CCER_CC3NE_Reset ((u16)0xFBFF)
+
+#define CCER_CC4E_Set ((u16)0x1000)
+#define CCER_CC4E_Reset ((u16)0xEFFF)
+
+#define BDTR_MOE_Set ((u16)0x8000)
+#define BDTR_MOE_Reset ((u16)0x7FFF)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+static void TI1_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter);
+static void TI2_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter);
+static void TI3_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter);
+static void TI4_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter);
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+/*******************************************************************************
+* Function Name : TIM_DeInit
+* Description : Deinitializes the TIMx peripheral registers to their default
+* reset values.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_DeInit(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+
+ switch (*(u32*)&TIMx)
+ {
+ case TIM1_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, DISABLE);
+ break;
+
+ case TIM2_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, DISABLE);
+ break;
+
+ case TIM3_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, DISABLE);
+ break;
+
+ case TIM4_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, DISABLE);
+ break;
+
+ case TIM5_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, DISABLE);
+ break;
+
+ case TIM6_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, DISABLE);
+ break;
+
+ case TIM7_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, DISABLE);
+ break;
+
+ case TIM8_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, DISABLE);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_TimeBaseInit
+* Description : Initializes the TIMx Time Base Unit peripheral according to
+* the specified parameters in the TIM_TimeBaseInitStruct.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_TimeBaseInitStruct: pointer to a TIM_TimeBaseInitTypeDef
+* structure that contains the configuration information for
+* the specified TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_COUNTER_MODE(TIM_TimeBaseInitStruct->TIM_CounterMode));
+ assert_param(IS_TIM_CKD_DIV(TIM_TimeBaseInitStruct->TIM_ClockDivision));
+
+ /* Select the Counter Mode and set the clock division */
+ TIMx->CR1 &= CR1_CKD_Mask & CR1_CounterMode_Mask;
+ TIMx->CR1 |= (u32)TIM_TimeBaseInitStruct->TIM_ClockDivision |
+ TIM_TimeBaseInitStruct->TIM_CounterMode;
+ /* Set the Autoreload value */
+ TIMx->ARR = TIM_TimeBaseInitStruct->TIM_Period ;
+
+ /* Set the Prescaler value */
+ TIMx->PSC = TIM_TimeBaseInitStruct->TIM_Prescaler;
+
+ /* Generate an update event to reload the Prescaler value immediatly */
+ TIMx->EGR = TIM_PSCReloadMode_Immediate;
+
+ if (((*(u32*)&TIMx) == TIM1_BASE) || ((*(u32*)&TIMx) == TIM8_BASE))
+ {
+ /* Set the Repetition Counter value */
+ TIMx->RCR = TIM_TimeBaseInitStruct->TIM_RepetitionCounter;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC1Init
+* Description : Initializes the TIMx Channel1 according to the specified
+* parameters in the TIM_OCInitStruct.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure
+* that contains the configuration information for the specified
+* TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+ u16 tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+ assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));
+
+ /* Disable the Channel 1: Reset the CC1E Bit */
+ TIMx->CCER &= CCER_CC1E_Reset;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = TIMx->CCER;
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = TIMx->CR2;
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmrx = TIMx->CCMR1;
+
+ /* Reset the Output Compare Mode Bits */
+ tmpccmrx &= CCMR_OC13M_Mask;
+
+ /* Select the Output Compare Mode */
+ tmpccmrx |= TIM_OCInitStruct->TIM_OCMode;
+
+ /* Reset the Output Polarity level */
+ tmpccer &= CCER_CC1P_Reset;
+
+ /* Set the Output Compare Polarity */
+ tmpccer |= TIM_OCInitStruct->TIM_OCPolarity;
+
+ /* Set the Output State */
+ tmpccer |= TIM_OCInitStruct->TIM_OutputState;
+
+ /* Set the Capture Compare Register value */
+ TIMx->CCR1 = TIM_OCInitStruct->TIM_Pulse;
+
+ if((*(u32*)&TIMx == TIM1_BASE) || (*(u32*)&TIMx == TIM8_BASE))
+ {
+ assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState));
+ assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity));
+ assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState));
+ assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+
+ /* Reset the Output N Polarity level */
+ tmpccer &= CCER_CC1NP_Reset;
+
+ /* Set the Output N Polarity */
+ tmpccer |= TIM_OCInitStruct->TIM_OCNPolarity;
+
+ /* Reset the Output N State */
+ tmpccer &= CCER_CC1NE_Reset;
+
+ /* Set the Output N State */
+ tmpccer |= TIM_OCInitStruct->TIM_OutputNState;
+
+ /* Reset the Ouput Compare and Output Compare N IDLE State */
+ tmpcr2 &= CR2_OIS1_Reset;
+ tmpcr2 &= CR2_OIS1N_Reset;
+
+ /* Set the Output Idle state */
+ tmpcr2 |= TIM_OCInitStruct->TIM_OCIdleState;
+
+ /* Set the Output N Idle state */
+ tmpcr2 |= TIM_OCInitStruct->TIM_OCNIdleState;
+ }
+ /* Write to TIMx CR2 */
+ TIMx->CR2 = tmpcr2;
+
+ /* Write to TIMx CCMR1 */
+ TIMx->CCMR1 = tmpccmrx;
+
+ /* Write to TIMx CCER */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC2Init
+* Description : Initializes the TIMx Channel2 according to the specified
+* parameters in the TIM_OCInitStruct.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure
+* that contains the configuration information for the specified
+* TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+ u16 tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+ assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));
+
+ /* Disable the Channel 2: Reset the CC2E Bit */
+ TIMx->CCER &= CCER_CC2E_Reset;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = TIMx->CCER;
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = TIMx->CR2;
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmrx = TIMx->CCMR1;
+
+ /* Reset the Output Compare Mode Bits */
+ tmpccmrx &= CCMR_OC24M_Mask;
+
+ /* Select the Output Compare Mode */
+ tmpccmrx |= (u16)(TIM_OCInitStruct->TIM_OCMode << 8);
+
+ /* Reset the Output Polarity level */
+ tmpccer &= CCER_CC2P_Reset;
+
+ /* Set the Output Compare Polarity */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OCPolarity << 4);
+
+ /* Set the Output State */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OutputState << 4);
+
+ /* Set the Capture Compare Register value */
+ TIMx->CCR2 = TIM_OCInitStruct->TIM_Pulse;
+
+ if((*(u32*)&TIMx == TIM1_BASE) || (*(u32*)&TIMx == TIM8_BASE))
+ {
+ assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState));
+ assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity));
+ assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState));
+ assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+
+ /* Reset the Output N Polarity level */
+ tmpccer &= CCER_CC2NP_Reset;
+
+ /* Set the Output N Polarity */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OCNPolarity << 4);
+
+ /* Reset the Output N State */
+ tmpccer &= CCER_CC2NE_Reset;
+
+ /* Set the Output N State */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OutputNState << 4);
+
+ /* Reset the Ouput Compare and Output Compare N IDLE State */
+ tmpcr2 &= CR2_OIS2_Reset;
+ tmpcr2 &= CR2_OIS2N_Reset;
+
+ /* Set the Output Idle state */
+ tmpcr2 |= (u16)(TIM_OCInitStruct->TIM_OCIdleState << 2);
+
+ /* Set the Output N Idle state */
+ tmpcr2 |= (u16)(TIM_OCInitStruct->TIM_OCNIdleState << 2);
+ }
+
+ /* Write to TIMx CR2 */
+ TIMx->CR2 = tmpcr2;
+
+ /* Write to TIMx CCMR1 */
+ TIMx->CCMR1 = tmpccmrx;
+
+ /* Write to TIMx CCER */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC3Init
+* Description : Initializes the TIMx Channel3 according to the specified
+* parameters in the TIM_OCInitStruct.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure
+* that contains the configuration information for the specified
+* TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+ u16 tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+ assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));
+
+ /* Disable the Channel 2: Reset the CC2E Bit */
+ TIMx->CCER &= CCER_CC3E_Reset;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = TIMx->CCER;
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = TIMx->CR2;
+
+ /* Get the TIMx CCMR2 register value */
+ tmpccmrx = TIMx->CCMR2;
+
+ /* Reset the Output Compare Mode Bits */
+ tmpccmrx &= CCMR_OC13M_Mask;
+
+ /* Select the Output Compare Mode */
+ tmpccmrx |= TIM_OCInitStruct->TIM_OCMode;
+
+ /* Reset the Output Polarity level */
+ tmpccer &= CCER_CC3P_Reset;
+
+ /* Set the Output Compare Polarity */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OCPolarity << 8);
+
+ /* Set the Output State */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OutputState << 8);
+
+ /* Set the Capture Compare Register value */
+ TIMx->CCR3 = TIM_OCInitStruct->TIM_Pulse;
+
+ if((*(u32*)&TIMx == TIM1_BASE) || (*(u32*)&TIMx == TIM8_BASE))
+ {
+ assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState));
+ assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity));
+ assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState));
+ assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+
+ /* Reset the Output N Polarity level */
+ tmpccer &= CCER_CC3NP_Reset;
+
+ /* Set the Output N Polarity */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OCNPolarity << 8);
+
+ /* Reset the Output N State */
+ tmpccer &= CCER_CC3NE_Reset;
+
+ /* Set the Output N State */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OutputNState << 8);
+
+ /* Reset the Ouput Compare and Output Compare N IDLE State */
+ tmpcr2 &= CR2_OIS3_Reset;
+ tmpcr2 &= CR2_OIS3N_Reset;
+
+ /* Set the Output Idle state */
+ tmpcr2 |= (u16)(TIM_OCInitStruct->TIM_OCIdleState << 4);
+
+ /* Set the Output N Idle state */
+ tmpcr2 |= (u16)(TIM_OCInitStruct->TIM_OCNIdleState << 4);
+ }
+
+ /* Write to TIMx CR2 */
+ TIMx->CR2 = tmpcr2;
+
+ /* Write to TIMx CCMR2 */
+ TIMx->CCMR2 = tmpccmrx;
+
+ /* Write to TIMx CCER */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC4Init
+* Description : Initializes the TIMx Channel4 according to the specified
+* parameters in the TIM_OCInitStruct.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure
+* that contains the configuration information for the specified
+* TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+ u16 tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+ assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));
+
+ /* Disable the Channel 2: Reset the CC4E Bit */
+ TIMx->CCER &= CCER_CC4E_Reset;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = TIMx->CCER;
+
+ /* Get the TIMx CR2 register value */
+ tmpcr2 = TIMx->CR2;
+
+ /* Get the TIMx CCMR2 register value */
+ tmpccmrx = TIMx->CCMR2;
+
+ /* Reset the Output Compare Mode Bits */
+ tmpccmrx &= CCMR_OC24M_Mask;
+
+ /* Select the Output Compare Mode */
+ tmpccmrx |= (u16)(TIM_OCInitStruct->TIM_OCMode << 8);
+
+ /* Reset the Output Polarity level */
+ tmpccer &= CCER_CC4P_Reset;
+
+ /* Set the Output Compare Polarity */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OCPolarity << 12);
+
+ /* Set the Output State */
+ tmpccer |= (u16)(TIM_OCInitStruct->TIM_OutputState << 12);
+
+ /* Set the Capture Compare Register value */
+ TIMx->CCR4 = TIM_OCInitStruct->TIM_Pulse;
+
+ if((*(u32*)&TIMx == TIM1_BASE) || (*(u32*)&TIMx == TIM8_BASE))
+ {
+ assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+
+ /* Reset the Ouput Compare IDLE State */
+ tmpcr2 &= CR2_OIS4_Reset;
+
+ /* Set the Output Idle state */
+ tmpcr2 |= (u16)(TIM_OCInitStruct->TIM_OCIdleState << 6);
+ }
+
+ /* Write to TIMx CR2 */
+ TIMx->CR2 = tmpcr2;
+
+ /* Write to TIMx CCMR2 */
+ TIMx->CCMR2 = tmpccmrx;
+
+ /* Write to TIMx CCER */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ICInit
+* Description : Initializes the TIM peripheral according to the specified
+* parameters in the TIM_ICInitStruct.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure
+* that contains the configuration information for the specified
+* TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_CHANNEL(TIM_ICInitStruct->TIM_Channel));
+ assert_param(IS_TIM_IC_POLARITY(TIM_ICInitStruct->TIM_ICPolarity));
+ assert_param(IS_TIM_IC_SELECTION(TIM_ICInitStruct->TIM_ICSelection));
+ assert_param(IS_TIM_IC_PRESCALER(TIM_ICInitStruct->TIM_ICPrescaler));
+ assert_param(IS_TIM_IC_FILTER(TIM_ICInitStruct->TIM_ICFilter));
+
+ if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1)
+ {
+ /* TI1 Configuration */
+ TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity,
+ TIM_ICInitStruct->TIM_ICSelection,
+ TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+ }
+ else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_2)
+ {
+ /* TI2 Configuration */
+ TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity,
+ TIM_ICInitStruct->TIM_ICSelection,
+ TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+ }
+ else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_3)
+ {
+ /* TI3 Configuration */
+ TI3_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity,
+ TIM_ICInitStruct->TIM_ICSelection,
+ TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC3Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+ }
+ else
+ {
+ /* TI4 Configuration */
+ TI4_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity,
+ TIM_ICInitStruct->TIM_ICSelection,
+ TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC4Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_PWMIConfig
+* Description : Configures the TIM peripheral according to the specified
+* parameters in the TIM_ICInitStruct to measure an external PWM
+* signal.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure
+* that contains the configuration information for the specified
+* TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct)
+{
+ u16 icoppositepolarity = TIM_ICPolarity_Rising;
+ u16 icoppositeselection = TIM_ICSelection_DirectTI;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Select the Opposite Input Polarity */
+ if (TIM_ICInitStruct->TIM_ICPolarity == TIM_ICPolarity_Rising)
+ {
+ icoppositepolarity = TIM_ICPolarity_Falling;
+ }
+ else
+ {
+ icoppositepolarity = TIM_ICPolarity_Rising;
+ }
+
+ /* Select the Opposite Input */
+ if (TIM_ICInitStruct->TIM_ICSelection == TIM_ICSelection_DirectTI)
+ {
+ icoppositeselection = TIM_ICSelection_IndirectTI;
+ }
+ else
+ {
+ icoppositeselection = TIM_ICSelection_DirectTI;
+ }
+
+ if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1)
+ {
+ /* TI1 Configuration */
+ TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection,
+ TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+
+ /* TI2 Configuration */
+ TI2_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+ }
+ else
+ {
+ /* TI2 Configuration */
+ TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection,
+ TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+
+ /* TI1 Configuration */
+ TI1_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter);
+
+ /* Set the Input Capture Prescaler value */
+ TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_BDTRConfig
+* Description : Configures the: Break feature, dead time, Lock level, the OSSI,
+* the OSSR State and the AOE(automatic output enable).
+* Input :- TIMx: where x can be 1 or 8 to select the TIM
+* - TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef
+* structure that contains the BDTR Register configuration
+* information for the TIM peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_TIM_OSSR_STATE(TIM_BDTRInitStruct->TIM_OSSRState));
+ assert_param(IS_TIM_OSSI_STATE(TIM_BDTRInitStruct->TIM_OSSIState));
+ assert_param(IS_TIM_LOCK_LEVEL(TIM_BDTRInitStruct->TIM_LOCKLevel));
+ assert_param(IS_TIM_BREAK_STATE(TIM_BDTRInitStruct->TIM_Break));
+ assert_param(IS_TIM_BREAK_POLARITY(TIM_BDTRInitStruct->TIM_BreakPolarity));
+ assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(TIM_BDTRInitStruct->TIM_AutomaticOutput));
+
+ /* Set the Lock level, the Break enable Bit and the Ploarity, the OSSR State,
+ the OSSI State, the dead time value and the Automatic Output Enable Bit */
+
+ TIMx->BDTR = (u32)TIM_BDTRInitStruct->TIM_OSSRState | TIM_BDTRInitStruct->TIM_OSSIState |
+ TIM_BDTRInitStruct->TIM_LOCKLevel | TIM_BDTRInitStruct->TIM_DeadTime |
+ TIM_BDTRInitStruct->TIM_Break | TIM_BDTRInitStruct->TIM_BreakPolarity |
+ TIM_BDTRInitStruct->TIM_AutomaticOutput;
+
+}
+
+/*******************************************************************************
+* Function Name : TIM_TimeBaseStructInit
+* Description : Fills each TIM_TimeBaseInitStruct member with its default value.
+* Input : - TIM_TimeBaseInitStruct : pointer to a TIM_TimeBaseInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct)
+{
+ /* Set the default configuration */
+ TIM_TimeBaseInitStruct->TIM_Period = 0xFFFF;
+ TIM_TimeBaseInitStruct->TIM_Prescaler = 0x0000;
+ TIM_TimeBaseInitStruct->TIM_ClockDivision = TIM_CKD_DIV1;
+ TIM_TimeBaseInitStruct->TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseInitStruct->TIM_RepetitionCounter = 0x0000;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OCStructInit
+* Description : Fills each TIM_OCInitStruct member with its default value.
+* Input : - TIM_OCInitStruct : pointer to a TIM_OCInitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+ /* Set the default configuration */
+ TIM_OCInitStruct->TIM_OCMode = TIM_OCMode_Timing;
+ TIM_OCInitStruct->TIM_OutputState = TIM_OutputState_Disable;
+ TIM_OCInitStruct->TIM_OutputNState = TIM_OutputNState_Disable;
+ TIM_OCInitStruct->TIM_Pulse = 0x0000;
+ TIM_OCInitStruct->TIM_OCPolarity = TIM_OCPolarity_High;
+ TIM_OCInitStruct->TIM_OCNPolarity = TIM_OCPolarity_High;
+ TIM_OCInitStruct->TIM_OCIdleState = TIM_OCIdleState_Reset;
+ TIM_OCInitStruct->TIM_OCNIdleState = TIM_OCNIdleState_Reset;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ICStructInit
+* Description : Fills each TIM_ICInitStruct member with its default value.
+* Input : - TIM_ICInitStruct : pointer to a TIM_ICInitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct)
+{
+ /* Set the default configuration */
+ TIM_ICInitStruct->TIM_Channel = TIM_Channel_1;
+ TIM_ICInitStruct->TIM_ICPolarity = TIM_ICPolarity_Rising;
+ TIM_ICInitStruct->TIM_ICSelection = TIM_ICSelection_DirectTI;
+ TIM_ICInitStruct->TIM_ICPrescaler = TIM_ICPSC_DIV1;
+ TIM_ICInitStruct->TIM_ICFilter = 0x00;
+}
+
+/*******************************************************************************
+* Function Name : TIM_BDTRStructInit
+* Description : Fills each TIM_BDTRInitStruct member with its default value.
+* Input : - TIM_BDTRInitStruct : pointer to a TIM_BDTRInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct)
+{
+ /* Set the default configuration */
+ TIM_BDTRInitStruct->TIM_OSSRState = TIM_OSSRState_Disable;
+ TIM_BDTRInitStruct->TIM_OSSIState = TIM_OSSIState_Disable;
+ TIM_BDTRInitStruct->TIM_LOCKLevel = TIM_LOCKLevel_OFF;
+ TIM_BDTRInitStruct->TIM_DeadTime = 0x00;
+ TIM_BDTRInitStruct->TIM_Break = TIM_Break_Disable;
+ TIM_BDTRInitStruct->TIM_BreakPolarity = TIM_BreakPolarity_Low;
+ TIM_BDTRInitStruct->TIM_AutomaticOutput = TIM_AutomaticOutput_Disable;
+}
+
+/*******************************************************************************
+* Function Name : TIM_Cmd
+* Description : Enables or disables the specified TIM peripheral.
+* Input : - TIMx: where x can be 1 to 8 to select the TIMx peripheral.
+* - NewState: new state of the TIMx peripheral.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the TIM Counter */
+ TIMx->CR1 |= CR1_CEN_Set;
+ }
+ else
+ {
+ /* Disable the TIM Counter */
+ TIMx->CR1 &= CR1_CEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_CtrlPWMOutputs
+* Description : Enables or disables the TIM peripheral Main Outputs.
+* Input :- TIMx: where x can be 1 or 8 to select the TIMx peripheral.
+* - NewState: new state of the TIM peripheral Main Outputs.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the TIM Main Output */
+ TIMx->BDTR |= BDTR_MOE_Set;
+ }
+ else
+ {
+ /* Disable the TIM Main Output */
+ TIMx->BDTR &= BDTR_MOE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_ITConfig
+* Description : Enables or disables the specified TIM interrupts.
+* Input : - TIMx: where x can be 1 to 8 to select the TIMx peripheral.
+* - TIM_IT: specifies the TIM interrupts sources to be enabled
+* or disabled.
+* This parameter can be any combination of the following values:
+* - TIM_IT_Update: TIM update Interrupt source
+* - TIM_IT_CC1: TIM Capture Compare 1 Interrupt source
+* - TIM_IT_CC2: TIM Capture Compare 2 Interrupt source
+* - TIM_IT_CC3: TIM Capture Compare 3 Interrupt source
+* - TIM_IT_CC4: TIM Capture Compare 4 Interrupt source
+* - TIM_IT_COM: TIM Commutation Interrupt source
+* - TIM_IT_Trigger: TIM Trigger Interrupt source
+* - TIM_IT_Break: TIM Break Interrupt source
+* - NewState: new state of the TIM interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ITConfig(TIM_TypeDef* TIMx, u16 TIM_IT, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_IT(TIM_IT));
+ assert_param(IS_TIM_PERIPH_IT((TIMx), (TIM_IT)));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the Interrupt sources */
+ TIMx->DIER |= TIM_IT;
+ }
+ else
+ {
+ /* Disable the Interrupt sources */
+ TIMx->DIER &= (u16)~TIM_IT;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_GenerateEvent
+* Description : Configures the TIMx event to be generate by software.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_EventSource: specifies the event source.
+* This parameter can be one or more of the following values:
+* - TIM_EventSource_Update: Timer update Event source
+* - TIM_EventSource_CC1: Timer Capture Compare 1 Event source
+* - TIM_EventSource_CC2: Timer Capture Compare 2 Event source
+* - TIM_EventSource_CC3: Timer Capture Compare 3 Event source
+* - TIM_EventSource_CC4: Timer Capture Compare 4 Event source
+* - TIM_EventSource_Trigger: Timer Trigger Event source
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_GenerateEvent(TIM_TypeDef* TIMx, u16 TIM_EventSource)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_EVENT_SOURCE(TIM_EventSource));
+ assert_param(IS_TIM_PERIPH_EVENT((TIMx), (TIM_EventSource)));
+
+ /* Set the event sources */
+ TIMx->EGR = TIM_EventSource;
+}
+
+/*******************************************************************************
+* Function Name : TIM_DMAConfig
+* Description : Configures the TIMx’s DMA interface.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_DMABase: DMA Base address.
+* This parameter can be one of the following values:
+* - TIM_DMABase_CR, TIM_DMABase_CR2, TIM_DMABase_SMCR,
+* TIM_DMABase_DIER, TIM1_DMABase_SR, TIM_DMABase_EGR,
+* TIM_DMABase_CCMR1, TIM_DMABase_CCMR2, TIM_DMABase_CCER,
+* TIM_DMABase_CNT, TIM_DMABase_PSC, TIM_DMABase_ARR,
+* TIM_DMABase_RCR, TIM_DMABase_CCR1, TIM_DMABase_CCR2,
+* TIM_DMABase_CCR3, TIM_DMABase_CCR4, TIM_DMABase_BDTR,
+* TIM_DMABase_DCR.
+* - TIM_DMABurstLength: DMA Burst length.
+* This parameter can be one value between:
+* TIM_DMABurstLength_1Byte and TIM_DMABurstLength_18Bytes.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_DMAConfig(TIM_TypeDef* TIMx, u16 TIM_DMABase, u16 TIM_DMABurstLength)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_DMA_BASE(TIM_DMABase));
+ assert_param(IS_TIM_DMA_LENGTH(TIM_DMABurstLength));
+
+ /* Set the DMA Base and the DMA Burst Length */
+ TIMx->DCR = TIM_DMABase | TIM_DMABurstLength;
+}
+
+/*******************************************************************************
+* Function Name : TIM_DMACmd
+* Description : Enables or disables the TIMx’s DMA Requests.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_DMASources: specifies the DMA Request sources.
+* This parameter can be any combination of the following values:
+* - TIM_DMA_Update: TIM update Interrupt source
+* - TIM_DMA_CC1: TIM Capture Compare 1 DMA source
+* - TIM_DMA_CC2: TIM Capture Compare 2 DMA source
+* - TIM_DMA_CC3: TIM Capture Compare 3 DMA source
+* - TIM_DMA_CC4: TIM Capture Compare 4 DMA source
+* - TIM_DMA_COM: TIM Commutation DMA source
+* - TIM_DMA_Trigger: TIM Trigger DMA source
+* - NewState: new state of the DMA Request sources.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_DMACmd(TIM_TypeDef* TIMx, u16 TIM_DMASource, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_DMA_SOURCE(TIM_DMASource));
+ assert_param(IS_TIM_PERIPH_DMA(TIMx, TIM_DMASource));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the DMA sources */
+ TIMx->DIER |= TIM_DMASource;
+ }
+ else
+ {
+ /* Disable the DMA sources */
+ TIMx->DIER &= (u16)~TIM_DMASource;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_InternalClockConfig
+* Description : Configures the TIMx interrnal Clock
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_InternalClockConfig(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Disable slave mode to clock the prescaler directly with the internal clock */
+ TIMx->SMCR &= SMCR_SMS_Mask;
+}
+/*******************************************************************************
+* Function Name : TIM_ITRxExternalClockConfig
+* Description : Configures the TIMx Internal Trigger as External Clock
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ITRSource: Trigger source.
+* This parameter can be one of the following values:
+* - TIM_TS_ITR0: Internal Trigger 0
+* - TIM_TS_ITR1: Internal Trigger 1
+* - TIM_TS_ITR2: Internal Trigger 2
+* - TIM_TS_ITR3: Internal Trigger 3
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, u16 TIM_InputTriggerSource)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_INTERNAL_TRIGGER_SELECTION(TIM_InputTriggerSource));
+
+ /* Select the Internal Trigger */
+ TIM_SelectInputTrigger(TIMx, TIM_InputTriggerSource);
+
+ /* Select the External clock mode1 */
+ TIMx->SMCR |= TIM_SlaveMode_External1;
+}
+/*******************************************************************************
+* Function Name : TIM_TIxExternalClockConfig
+* Description : Configures the TIMx Trigger as External Clock
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_TIxExternalCLKSource: Trigger source.
+* This parameter can be one of the following values:
+* - TIM_TIxExternalCLK1Source_TI1ED: TI1 Edge Detector
+* - TIM_TIxExternalCLK1Source_TI1: Filtered Timer Input 1
+* - TIM_TIxExternalCLK1Source_TI2: Filtered Timer Input 2
+* - TIM_ICPolarity: specifies the TIx Polarity.
+* This parameter can be:
+* - TIM_ICPolarity_Rising
+* - TIM_ICPolarity_Falling
+* - ICFilter : specifies the filter value.
+* This parameter must be a value between 0x0 and 0xF.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, u16 TIM_TIxExternalCLKSource,
+ u16 TIM_ICPolarity, u16 ICFilter)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_TIXCLK_SOURCE(TIM_TIxExternalCLKSource));
+ assert_param(IS_TIM_IC_POLARITY(TIM_ICPolarity));
+ assert_param(IS_TIM_IC_FILTER(ICFilter));
+
+ /* Configure the Timer Input Clock Source */
+ if (TIM_TIxExternalCLKSource == TIM_TIxExternalCLK1Source_TI2)
+ {
+ TI2_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter);
+ }
+ else
+ {
+ TI1_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter);
+ }
+
+ /* Select the Trigger source */
+ TIM_SelectInputTrigger(TIMx, TIM_TIxExternalCLKSource);
+
+ /* Select the External clock mode1 */
+ TIMx->SMCR |= TIM_SlaveMode_External1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ETRClockMode1Config
+* Description : Configures the External clock Mode1
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ExtTRGPrescaler: The external Trigger Prescaler.
+* It can be one of the following values:
+* - TIM_ExtTRGPSC_OFF
+* - TIM_ExtTRGPSC_DIV2
+* - TIM_ExtTRGPSC_DIV4
+* - TIM_ExtTRGPSC_DIV8.
+* - TIM_ExtTRGPolarity: The external Trigger Polarity.
+* It can be one of the following values:
+* - TIM_ExtTRGPolarity_Inverted
+* - TIM_ExtTRGPolarity_NonInverted
+* - ExtTRGFilter: External Trigger Filter.
+* This parameter must be a value between 0x00 and 0x0F
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, u16 TIM_ExtTRGPrescaler, u16 TIM_ExtTRGPolarity,
+ u16 ExtTRGFilter)
+{
+ u16 tmpsmcr = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler));
+ assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity));
+ assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter));
+
+ /* Configure the ETR Clock source */
+ TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter);
+
+ /* Get the TIMx SMCR register value */
+ tmpsmcr = TIMx->SMCR;
+
+ /* Reset the SMS Bits */
+ tmpsmcr &= SMCR_SMS_Mask;
+ /* Select the External clock mode1 */
+ tmpsmcr |= TIM_SlaveMode_External1;
+
+ /* Select the Trigger selection : ETRF */
+ tmpsmcr &= SMCR_TS_Mask;
+ tmpsmcr |= TIM_TS_ETRF;
+
+ /* Write to TIMx SMCR */
+ TIMx->SMCR = tmpsmcr;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ETRClockMode2Config
+* Description : Configures the External clock Mode2
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ExtTRGPrescaler: The external Trigger Prescaler.
+* It can be one of the following values:
+* - TIM_ExtTRGPSC_OFF
+* - TIM_ExtTRGPSC_DIV2
+* - TIM_ExtTRGPSC_DIV4
+* - TIM_ExtTRGPSC_DIV8
+* - TIM_ExtTRGPolarity: The external Trigger Polarity.
+* It can be one of the following values:
+* - TIM_ExtTRGPolarity_Inverted
+* - TIM_ExtTRGPolarity_NonInverted
+* - ExtTRGFilter: External Trigger Filter.
+* This parameter must be a value between 0x00 and 0x0F
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, u16 TIM_ExtTRGPrescaler,
+ u16 TIM_ExtTRGPolarity, u16 ExtTRGFilter)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler));
+ assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity));
+ assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter));
+
+ /* Configure the ETR Clock source */
+ TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter);
+
+ /* Enable the External clock mode2 */
+ TIMx->SMCR |= SMCR_ECE_Set;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ETRConfig
+* Description : Configures the TIMx External Trigger (ETR).
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ExtTRGPrescaler: The external Trigger Prescaler.
+* This parameter can be one of the following values:
+* - TIM_ExtTRGPSC_OFF
+* - TIM_ExtTRGPSC_DIV2
+* - TIM_ExtTRGPSC_DIV4
+* - TIM_ExtTRGPSC_DIV8
+* - TIM_ExtTRGPolarity: The external Trigger Polarity.
+* This parameter can be one of the following values:
+* - TIM_ExtTRGPolarity_Inverted
+* - TIM_ExtTRGPolarity_NonInverted
+* - ExtTRGFilter: External Trigger Filter.
+* This parameter must be a value between 0x00 and 0x0F.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ETRConfig(TIM_TypeDef* TIMx, u16 TIM_ExtTRGPrescaler, u16 TIM_ExtTRGPolarity,
+ u16 ExtTRGFilter)
+{
+ u16 tmpsmcr = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler));
+ assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity));
+ assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter));
+
+ tmpsmcr = TIMx->SMCR;
+
+ /* Reset the ETR Bits */
+ tmpsmcr &= SMCR_ETR_Mask;
+
+ /* Set the Prescaler, the Filter value and the Polarity */
+ tmpsmcr |= TIM_ExtTRGPrescaler | TIM_ExtTRGPolarity | (u16)(ExtTRGFilter << 8);
+
+ /* Write to TIMx SMCR */
+ TIMx->SMCR = tmpsmcr;
+}
+
+/*******************************************************************************
+* Function Name : TIM_PrescalerConfig
+* Description : Configures the TIMx Prescaler.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - Prescaler: specifies the Prescaler Register value
+* - TIM_PSCReloadMode: specifies the TIM Prescaler Reload mode
+* This parameter can be one of the following values:
+* - TIM_PSCReloadMode_Update: The Prescaler is loaded at
+* the update event.
+* - TIM_PSCReloadMode_Immediate: The Prescaler is loaded
+* immediatly.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_PrescalerConfig(TIM_TypeDef* TIMx, u16 Prescaler, u16 TIM_PSCReloadMode)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_PRESCALER_RELOAD(TIM_PSCReloadMode));
+
+ /* Set the Prescaler value */
+ TIMx->PSC = Prescaler;
+
+ /* Set or reset the UG Bit */
+ TIMx->EGR = TIM_PSCReloadMode;
+}
+
+/*******************************************************************************
+* Function Name : TIM_CounterModeConfig
+* Description : Specifies the TIMx Counter Mode to be used.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_CounterMode: specifies the Counter Mode to be used
+* This parameter can be one of the following values:
+* - TIM_CounterMode_Up: TIM Up Counting Mode
+* - TIM_CounterMode_Down: TIM Down Counting Mode
+* - TIM_CounterMode_CenterAligned1: TIM Center Aligned Mode1
+* - TIM_CounterMode_CenterAligned2: TIM Center Aligned Mode2
+* - TIM_CounterMode_CenterAligned3: TIM Center Aligned Mode3
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_CounterModeConfig(TIM_TypeDef* TIMx, u16 TIM_CounterMode)
+{
+ u16 tmpcr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_COUNTER_MODE(TIM_CounterMode));
+
+ tmpcr1 = TIMx->CR1;
+
+ /* Reset the CMS and DIR Bits */
+ tmpcr1 &= CR1_CounterMode_Mask;
+
+ /* Set the Counter Mode */
+ tmpcr1 |= TIM_CounterMode;
+
+ /* Write to TIMx CR1 register */
+ TIMx->CR1 = tmpcr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectInputTrigger
+* Description : Selects the Input Trigger source
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_InputTriggerSource: The Input Trigger source.
+* This parameter can be one of the following values:
+* - TIM_TS_ITR0: Internal Trigger 0
+* - TIM_TS_ITR1: Internal Trigger 1
+* - TIM_TS_ITR2: Internal Trigger 2
+* - TIM_TS_ITR3: Internal Trigger 3
+* - TIM_TS_TI1F_ED: TI1 Edge Detector
+* - TIM_TS_TI1FP1: Filtered Timer Input 1
+* - TIM_TS_TI2FP2: Filtered Timer Input 2
+* - TIM_TS_ETRF: External Trigger input
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, u16 TIM_InputTriggerSource)
+{
+ u16 tmpsmcr = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_TRIGGER_SELECTION(TIM_InputTriggerSource));
+
+ /* Get the TIMx SMCR register value */
+ tmpsmcr = TIMx->SMCR;
+
+ /* Reset the TS Bits */
+ tmpsmcr &= SMCR_TS_Mask;
+
+ /* Set the Input Trigger source */
+ tmpsmcr |= TIM_InputTriggerSource;
+
+ /* Write to TIMx SMCR */
+ TIMx->SMCR = tmpsmcr;
+}
+
+/*******************************************************************************
+* Function Name : TIM_EncoderInterfaceConfig
+* Description : Configures the TIMx Encoder Interface.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_EncoderMode: specifies the TIMx Encoder Mode.
+* This parameter can be one of the following values:
+* - TIM_EncoderMode_TI1: Counter counts on TI1FP1 edge
+* depending on TI2FP2 level.
+* - TIM_EncoderMode_TI2: Counter counts on TI2FP2 edge
+* depending on TI1FP1 level.
+* - TIM_EncoderMode_TI12: Counter counts on both TI1FP1 and
+* TI2FP2 edges depending on the level of the other input.
+* - TIM_IC1Polarity: specifies the IC1 Polarity
+* This parmeter can be one of the following values:
+* - TIM_ICPolarity_Falling: IC Falling edge.
+* - TIM_ICPolarity_Rising: IC Rising edge.
+* - TIM_IC2Polarity: specifies the IC2 Polarity
+* This parmeter can be one of the following values:
+* - TIM_ICPolarity_Falling: IC Falling edge.
+* - TIM_ICPolarity_Rising: IC Rising edge.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, u16 TIM_EncoderMode,
+ u16 TIM_IC1Polarity, u16 TIM_IC2Polarity)
+{
+ u16 tmpsmcr = 0;
+ u16 tmpccmr1 = 0;
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_ENCODER_MODE(TIM_EncoderMode));
+ assert_param(IS_TIM_IC_POLARITY(TIM_IC1Polarity));
+ assert_param(IS_TIM_IC_POLARITY(TIM_IC2Polarity));
+
+ /* Get the TIMx SMCR register value */
+ tmpsmcr = TIMx->SMCR;
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Get the TIMx CCER register value */
+ tmpccer = TIMx->CCER;
+
+ /* Set the encoder Mode */
+ tmpsmcr &= SMCR_SMS_Mask;
+ tmpsmcr |= TIM_EncoderMode;
+
+ /* Select the Capture Compare 1 and the Capture Compare 2 as input */
+ tmpccmr1 &= CCMR_CC13S_Mask & CCMR_CC24S_Mask;
+ tmpccmr1 |= CCMR_TI13Direct_Set | CCMR_TI24Direct_Set;
+
+ /* Set the TI1 and the TI2 Polarities */
+ tmpccer &= CCER_CC1P_Reset & CCER_CC2P_Reset;
+ tmpccer |= (TIM_IC1Polarity | (u16)(TIM_IC2Polarity << 4));
+
+ /* Write to TIMx SMCR */
+ TIMx->SMCR = tmpsmcr;
+
+ /* Write to TIMx CCMR1 */
+ TIMx->CCMR1 = tmpccmr1;
+
+ /* Write to TIMx CCER */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ForcedOC1Config
+* Description : Forces the TIMx output 1 waveform to active or inactive level.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ForcedAction: specifies the forced Action to be set to
+* the output waveform.
+* This parameter can be one of the following values:
+* - TIM_ForcedAction_Active: Force active level on OC1REF
+* - TIM_ForcedAction_InActive: Force inactive level on
+* OC1REF.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC1M Bits */
+ tmpccmr1 &= CCMR_OC13M_Mask;
+
+ /* Configure The Forced output Mode */
+ tmpccmr1 |= TIM_ForcedAction;
+
+ /* Write to TIMx CCMR1 register */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ForcedOC2Config
+* Description : Forces the TIMx output 2 waveform to active or inactive level.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ForcedAction: specifies the forced Action to be set to
+* the output waveform.
+* This parameter can be one of the following values:
+* - TIM_ForcedAction_Active: Force active level on OC2REF
+* - TIM_ForcedAction_InActive: Force inactive level on
+* OC2REF.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC2M Bits */
+ tmpccmr1 &= CCMR_OC24M_Mask;
+
+ /* Configure The Forced output Mode */
+ tmpccmr1 |= (u16)(TIM_ForcedAction << 8);
+
+ /* Write to TIMx CCMR1 register */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ForcedOC3Config
+* Description : Forces the TIMx output 3 waveform to active or inactive level.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ForcedAction: specifies the forced Action to be set to
+* the output waveform.
+* This parameter can be one of the following values:
+* - TIM_ForcedAction_Active: Force active level on OC3REF
+* - TIM_ForcedAction_InActive: Force inactive level on
+* OC3REF.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC1M Bits */
+ tmpccmr2 &= CCMR_OC13M_Mask;
+
+ /* Configure The Forced output Mode */
+ tmpccmr2 |= TIM_ForcedAction;
+
+ /* Write to TIMx CCMR2 register */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ForcedOC4Config
+* Description : Forces the TIMx output 4 waveform to active or inactive level.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ForcedAction: specifies the forced Action to be set to
+* the output waveform.
+* This parameter can be one of the following values:
+* - TIM_ForcedAction_Active: Force active level on OC4REF
+* - TIM_ForcedAction_InActive: Force inactive level on
+* OC4REF.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, u16 TIM_ForcedAction)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC2M Bits */
+ tmpccmr2 &= CCMR_OC24M_Mask;
+
+ /* Configure The Forced output Mode */
+ tmpccmr2 |= (u16)(TIM_ForcedAction << 8);
+
+ /* Write to TIMx CCMR2 register */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ARRPreloadConfig
+* Description : Enables or disables TIMx peripheral Preload register on ARR.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - NewState: new state of the TIMx peripheral Preload register
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Set the ARR Preload Bit */
+ TIMx->CR1 |= CR1_ARPE_Set;
+ }
+ else
+ {
+ /* Reset the ARR Preload Bit */
+ TIMx->CR1 &= CR1_ARPE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectCOM
+* Description : Selects the TIM peripheral Commutation event.
+* Input :- TIMx: where x can be 1 or 8 to select the TIMx peripheral
+* - NewState: new state of the Commutation event.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Set the COM Bit */
+ TIMx->CR2 |= CR2_CCUS_Set;
+ }
+ else
+ {
+ /* Reset the COM Bit */
+ TIMx->CR2 &= CR2_CCUS_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectCCDMA
+* Description : Selects the TIMx peripheral Capture Compare DMA source.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - NewState: new state of the Capture Compare DMA source
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Set the CCDS Bit */
+ TIMx->CR2 |= CR2_CCDS_Set;
+ }
+ else
+ {
+ /* Reset the CCDS Bit */
+ TIMx->CR2 &= CR2_CCDS_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_CCPreloadControl
+* Description : Sets or Resets the TIM peripheral Capture Compare Preload
+* Control bit.
+* Input :- TIMx: where x can be 1 or 8 to select the TIMx peripheral
+* - NewState: new state of the Capture Compare Preload Control bit
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Set the CCPC Bit */
+ TIMx->CR2 |= CR2_CCPC_Set;
+ }
+ else
+ {
+ /* Reset the CCPC Bit */
+ TIMx->CR2 &= CR2_CCPC_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC1PreloadConfig
+* Description : Enables or disables the TIMx peripheral Preload register on CCR1.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPreload: new state of the TIMx peripheral Preload
+* register
+* This parameter can be one of the following values:
+* - TIM_OCPreload_Enable
+* - TIM_OCPreload_Disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC1PE Bit */
+ tmpccmr1 &= CCMR_OC13PE_Reset;
+
+ /* Enable or Disable the Output Compare Preload feature */
+ tmpccmr1 |= TIM_OCPreload;
+
+ /* Write to TIMx CCMR1 register */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC2PreloadConfig
+* Description : Enables or disables the TIMx peripheral Preload register on CCR2.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPreload: new state of the TIMx peripheral Preload
+* register
+* This parameter can be one of the following values:
+* - TIM_OCPreload_Enable
+* - TIM_OCPreload_Disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC2PE Bit */
+ tmpccmr1 &= CCMR_OC24PE_Reset;
+
+ /* Enable or Disable the Output Compare Preload feature */
+ tmpccmr1 |= (u16)(TIM_OCPreload << 8);
+
+ /* Write to TIMx CCMR1 register */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC3PreloadConfig
+* Description : Enables or disables the TIMx peripheral Preload register on CCR3.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPreload: new state of the TIMx peripheral Preload
+* register
+* This parameter can be one of the following values:
+* - TIM_OCPreload_Enable
+* - TIM_OCPreload_Disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC3PE Bit */
+ tmpccmr2 &= CCMR_OC13PE_Reset;
+
+ /* Enable or Disable the Output Compare Preload feature */
+ tmpccmr2 |= TIM_OCPreload;
+
+ /* Write to TIMx CCMR2 register */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC4PreloadConfig
+* Description : Enables or disables the TIMx peripheral Preload register on CCR4.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPreload: new state of the TIMx peripheral Preload
+* register
+* This parameter can be one of the following values:
+* - TIM_OCPreload_Enable
+* - TIM_OCPreload_Disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, u16 TIM_OCPreload)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC4PE Bit */
+ tmpccmr2 &= CCMR_OC24PE_Reset;
+
+ /* Enable or Disable the Output Compare Preload feature */
+ tmpccmr2 |= (u16)(TIM_OCPreload << 8);
+
+ /* Write to TIMx CCMR2 register */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC1FastConfig
+* Description : Configures the TIMx Output Compare 1 Fast feature.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCFast_Enable: TIM output compare fast enable
+* - TIM_OCFast_Disable: TIM output compare fast disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC1FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC1FE Bit */
+ tmpccmr1 &= CCMR_OC13FE_Reset;
+
+ /* Enable or Disable the Output Compare Fast Bit */
+ tmpccmr1 |= TIM_OCFast;
+
+ /* Write to TIMx CCMR1 */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC2FastConfig
+* Description : Configures the TIMx Output Compare 2 Fast feature.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCFast_Enable: TIM output compare fast enable
+* - TIM_OCFast_Disable: TIM output compare fast disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC2FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+
+ /* Get the TIMx CCMR1 register value */
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC2FE Bit */
+ tmpccmr1 &= CCMR_OC24FE_Reset;
+
+ /* Enable or Disable the Output Compare Fast Bit */
+ tmpccmr1 |= (u16)(TIM_OCFast << 8);
+
+ /* Write to TIMx CCMR1 */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC3FastConfig
+* Description : Configures the TIMx Output Compare 3 Fast feature.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCFast_Enable: TIM output compare fast enable
+* - TIM_OCFast_Disable: TIM output compare fast disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC3FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+
+ /* Get the TIMx CCMR2 register value */
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC3FE Bit */
+ tmpccmr2 &= CCMR_OC13FE_Reset;
+
+ /* Enable or Disable the Output Compare Fast Bit */
+ tmpccmr2 |= TIM_OCFast;
+
+ /* Write to TIMx CCMR2 */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC4FastConfig
+* Description : Configures the TIMx Output Compare 4 Fast feature.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCFast_Enable: TIM output compare fast enable
+* - TIM_OCFast_Disable: TIM output compare fast disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC4FastConfig(TIM_TypeDef* TIMx, u16 TIM_OCFast)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+
+ /* Get the TIMx CCMR2 register value */
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC4FE Bit */
+ tmpccmr2 &= CCMR_OC24FE_Reset;
+
+ /* Enable or Disable the Output Compare Fast Bit */
+ tmpccmr2 |= (u16)(TIM_OCFast << 8);
+
+ /* Write to TIMx CCMR2 */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ClearOC1Ref
+* Description : Clears or safeguards the OCREF1 signal on an external event
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCClear_Enable: TIM Output clear enable
+* - TIM_OCClear_Disable: TIM Output clear disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC1CE Bit */
+ tmpccmr1 &= CCMR_OC13CE_Reset;
+
+ /* Enable or Disable the Output Compare Clear Bit */
+ tmpccmr1 |= TIM_OCClear;
+
+ /* Write to TIMx CCMR1 register */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ClearOC2Ref
+* Description : Clears or safeguards the OCREF2 signal on an external event
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCClear_Enable: TIM Output clear enable
+* - TIM_OCClear_Disable: TIM Output clear disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear)
+{
+ u16 tmpccmr1 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+
+ tmpccmr1 = TIMx->CCMR1;
+
+ /* Reset the OC2CE Bit */
+ tmpccmr1 &= CCMR_OC24CE_Reset;
+
+ /* Enable or Disable the Output Compare Clear Bit */
+ tmpccmr1 |= (u16)(TIM_OCClear << 8);
+
+ /* Write to TIMx CCMR1 register */
+ TIMx->CCMR1 = tmpccmr1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ClearOC3Ref
+* Description : Clears or safeguards the OCREF3 signal on an external event
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCClear_Enable: TIM Output clear enable
+* - TIM_OCClear_Disable: TIM Output clear disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC3CE Bit */
+ tmpccmr2 &= CCMR_OC13CE_Reset;
+
+ /* Enable or Disable the Output Compare Clear Bit */
+ tmpccmr2 |= TIM_OCClear;
+
+ /* Write to TIMx CCMR2 register */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ClearOC4Ref
+* Description : Clears or safeguards the OCREF4 signal on an external event
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+* This parameter can be one of the following values:
+* - TIM_OCClear_Enable: TIM Output clear enable
+* - TIM_OCClear_Disable: TIM Output clear disable
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, u16 TIM_OCClear)
+{
+ u16 tmpccmr2 = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+
+ tmpccmr2 = TIMx->CCMR2;
+
+ /* Reset the OC4CE Bit */
+ tmpccmr2 &= CCMR_OC24CE_Reset;
+
+ /* Enable or Disable the Output Compare Clear Bit */
+ tmpccmr2 |= (u16)(TIM_OCClear << 8);
+
+ /* Write to TIMx CCMR2 register */
+ TIMx->CCMR2 = tmpccmr2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC1PolarityConfig
+* Description : Configures the TIMx channel 1 polarity.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPolarity: specifies the OC1 Polarity
+* This parmeter can be one of the following values:
+* - TIM_OCPolarity_High: Output Compare active high
+* - TIM_OCPolarity_Low: Output Compare active low
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity)
+{
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+
+ tmpccer = TIMx->CCER;
+
+ /* Set or Reset the CC1P Bit */
+ tmpccer &= CCER_CC1P_Reset;
+ tmpccer |= TIM_OCPolarity;
+
+ /* Write to TIMx CCER register */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC1NPolarityConfig
+* Description : Configures the TIMx Channel 1N polarity.
+* Input : - TIMx: where x can be 1 or 8 to select the TIM peripheral.
+* - TIM_OCNPolarity: specifies the OC1N Polarity
+* This parmeter can be one of the following values:
+* - TIM_OCNPolarity_High: Output Compare active high
+* - TIM_OCNPolarity_Low: Output Compare active low
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCNPolarity)
+{
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity));
+
+ tmpccer = TIMx->CCER;
+
+ /* Set or Reset the CC1NP Bit */
+ tmpccer &= CCER_CC1NP_Reset;
+ tmpccer |= TIM_OCNPolarity;
+
+ /* Write to TIMx CCER register */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC2PolarityConfig
+* Description : Configures the TIMx channel 2 polarity.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPolarity: specifies the OC2 Polarity
+* This parmeter can be one of the following values:
+* - TIM_OCPolarity_High: Output Compare active high
+* - TIM_OCPolarity_Low: Output Compare active low
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity)
+{
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+
+ tmpccer = TIMx->CCER;
+
+ /* Set or Reset the CC2P Bit */
+ tmpccer &= CCER_CC2P_Reset;
+ tmpccer |= (u16)(TIM_OCPolarity << 4);
+
+ /* Write to TIMx CCER register */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC2NPolarityConfig
+* Description : Configures the TIMx Channel 2N polarity.
+* Input : - TIMx: where x can be 1 or 8 to select the TIM peripheral.
+* - TIM_OCNPolarity: specifies the OC2N Polarity
+* This parmeter can be one of the following values:
+* - TIM_OCNPolarity_High: Output Compare active high
+* - TIM_OCNPolarity_Low: Output Compare active low
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCNPolarity)
+{
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity));
+
+ tmpccer = TIMx->CCER;
+
+ /* Set or Reset the CC2NP Bit */
+ tmpccer &= CCER_CC2NP_Reset;
+ tmpccer |= (u16)(TIM_OCNPolarity << 4);
+
+ /* Write to TIMx CCER register */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC3PolarityConfig
+* Description : Configures the TIMx channel 3 polarity.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPolarity: specifies the OC3 Polarity
+* This parmeter can be one of the following values:
+* - TIM_OCPolarity_High: Output Compare active high
+* - TIM_OCPolarity_Low: Output Compare active low
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity)
+{
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+
+ tmpccer = TIMx->CCER;
+
+ /* Set or Reset the CC3P Bit */
+ tmpccer &= CCER_CC3P_Reset;
+ tmpccer |= (u16)(TIM_OCPolarity << 8);
+
+ /* Write to TIMx CCER register */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC3NPolarityConfig
+* Description : Configures the TIMx Channel 3N polarity.
+* Input : - TIMx: where x can be 1 or 8 to select the TIM peripheral.
+* - TIM_OCNPolarity: specifies the OC3N Polarity
+* This parmeter can be one of the following values:
+* - TIM_OCNPolarity_High: Output Compare active high
+* - TIM_OCNPolarity_Low: Output Compare active low
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCNPolarity)
+{
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity));
+
+ tmpccer = TIMx->CCER;
+
+ /* Set or Reset the CC3NP Bit */
+ tmpccer &= CCER_CC3NP_Reset;
+ tmpccer |= (u16)(TIM_OCNPolarity << 8);
+
+ /* Write to TIMx CCER register */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_OC4PolarityConfig
+* Description : Configures the TIMx channel 4 polarity.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_OCPolarity: specifies the OC4 Polarity
+* This parmeter can be one of the following values:
+* - TIM_OCPolarity_High: Output Compare active high
+* - TIM_OCPolarity_Low: Output Compare active low
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, u16 TIM_OCPolarity)
+{
+ u16 tmpccer = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+
+ tmpccer = TIMx->CCER;
+
+ /* Set or Reset the CC4P Bit */
+ tmpccer &= CCER_CC4P_Reset;
+ tmpccer |= (u16)(TIM_OCPolarity << 12);
+
+ /* Write to TIMx CCER register */
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TIM_CCxCmd
+* Description : Enables or disables the TIM Capture Compare Channel x.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_Channel: specifies the TIM Channel
+* This parmeter can be one of the following values:
+* - TIM_Channel_1: TIM Channel 1
+* - TIM_Channel_2: TIM Channel 2
+* - TIM_Channel_3: TIM Channel 3
+* - TIM_Channel_4: TIM Channel 4
+* - TIM_CCx: specifies the TIM Channel CCxE bit new state.
+* This parameter can be: TIM_CCx_Enable or TIM_CCx_Disable.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_CCxCmd(TIM_TypeDef* TIMx, u16 TIM_Channel, u16 TIM_CCx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_CHANNEL(TIM_Channel));
+ assert_param(IS_TIM_CCX(TIM_CCx));
+
+ /* Reset the CCxE Bit */
+ TIMx->CCER &= (u16)(~((u16)(CCER_CCE_Set << TIM_Channel)));
+
+ /* Set or reset the CCxE Bit */
+ TIMx->CCER |= (u16)(TIM_CCx << TIM_Channel);
+}
+
+/*******************************************************************************
+* Function Name : TIM_CCxNCmd
+* Description : Enables or disables the TIM Capture Compare Channel xN.
+* Input :- TIMx: where x can be 1 or 8 to select the TIM peripheral.
+* - TIM_Channel: specifies the TIM Channel
+* This parmeter can be one of the following values:
+* - TIM_Channel_1: TIM Channel 1
+* - TIM_Channel_2: TIM Channel 2
+* - TIM_Channel_3: TIM Channel 3
+* - TIM_CCx: specifies the TIM Channel CCxNE bit new state.
+* This parameter can be: TIM_CCxN_Enable or TIM_CCxN_Disable.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_CCxNCmd(TIM_TypeDef* TIMx, u16 TIM_Channel, u16 TIM_CCxN)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_18_PERIPH(TIMx));
+ assert_param(IS_TIM_COMPLEMENTARY_CHANNEL(TIM_Channel));
+ assert_param(IS_TIM_CCXN(TIM_CCxN));
+
+ /* Reset the CCxNE Bit */
+ TIMx->CCER &= (u16)(~((u16)(CCER_CCNE_Set << TIM_Channel)));
+
+ /* Set or reset the CCxNE Bit */
+ TIMx->CCER |= (u16)(TIM_CCxN << TIM_Channel);
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectOCxM
+* Description : Selects the TIM Ouput Compare Mode.
+* This function disables the selected channel before changing
+* the Ouput Compare Mode. User has to enable this channel using
+* TIM_CCxCmd and TIM_CCxNCmd functions.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_Channel: specifies the TIM Channel
+* This parmeter can be one of the following values:
+* - TIM_Channel_1: TIM Channel 1
+* - TIM_Channel_2: TIM Channel 2
+* - TIM_Channel_3: TIM Channel 3
+* - TIM_Channel_4: TIM Channel 4
+* - TIM_OCMode: specifies the TIM Output Compare Mode.
+* This paramter can be one of the following values:
+* - TIM_OCMode_Timing
+* - TIM_OCMode_Active
+* - TIM_OCMode_Toggle
+* - TIM_OCMode_PWM1
+* - TIM_OCMode_PWM2
+* - TIM_ForcedAction_Active
+* - TIM_ForcedAction_InActive
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectOCxM(TIM_TypeDef* TIMx, u16 TIM_Channel, u16 TIM_OCMode)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_CHANNEL(TIM_Channel));
+ assert_param(IS_TIM_OCM(TIM_OCMode));
+
+ /* Disable the Channel: Reset the CCxE Bit */
+ TIMx->CCER &= (u16)(~((u16)(CCER_CCE_Set << TIM_Channel)));
+
+ if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3))
+ {
+ /* Reset the OCxM bits in the CCMRx register */
+ *((vu32 *)((*(u32*)&TIMx) + CCMR_Offset + (TIM_Channel>>1))) &= CCMR_OC13M_Mask;
+
+ /* Configure the OCxM bits in the CCMRx register */
+ *((vu32 *)((*(u32*)&TIMx) + CCMR_Offset + (TIM_Channel>>1))) = TIM_OCMode;
+
+ }
+ else
+ {
+ /* Reset the OCxM bits in the CCMRx register */
+ *((vu32 *)((*(u32*)&TIMx) + CCMR_Offset + ((u16)(TIM_Channel - 4)>> 1))) &= CCMR_OC24M_Mask;
+
+ /* Configure the OCxM bits in the CCMRx register */
+ *((vu32 *)((*(u32*)&TIMx) + CCMR_Offset + ((u16)(TIM_Channel - 4)>> 1))) = (u16)(TIM_OCMode << 8);
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_UpdateDisableConfig
+* Description : Enables or Disables the TIMx Update event.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - NewState: new state of the TIMx UDIS bit
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Set the Update Disable Bit */
+ TIMx->CR1 |= CR1_UDIS_Set;
+ }
+ else
+ {
+ /* Reset the Update Disable Bit */
+ TIMx->CR1 &= CR1_UDIS_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_UpdateRequestConfig
+* Description : Configures the TIMx Update Request Interrupt source.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_UpdateSource: specifies the Update source.
+* This parameter can be one of the following values:
+* - TIM_UpdateSource_Regular
+* - TIM_UpdateSource_Global
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, u16 TIM_UpdateSource)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_UPDATE_SOURCE(TIM_UpdateSource));
+
+ if (TIM_UpdateSource != TIM_UpdateSource_Global)
+ {
+ /* Set the URS Bit */
+ TIMx->CR1 |= CR1_URS_Set;
+ }
+ else
+ {
+ /* Reset the URS Bit */
+ TIMx->CR1 &= CR1_URS_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectHallSensor
+* Description : Enables or disables the TIMx’s Hall sensor interface.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+* - NewState: new state of the TIMx Hall sensor interface.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Set the TI1S Bit */
+ TIMx->CR2 |= CR2_TI1S_Set;
+ }
+ else
+ {
+ /* Reset the TI1S Bit */
+ TIMx->CR2 &= CR2_TI1S_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectOnePulseMode
+* Description : Selects the TIMx’s One Pulse Mode.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_OPMode: specifies the OPM Mode to be used.
+* This parameter can be one of the following values:
+* - TIM_OPMode_Single
+* - TIM_OPMode_Repetitive
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, u16 TIM_OPMode)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_OPM_MODE(TIM_OPMode));
+
+ /* Reset the OPM Bit */
+ TIMx->CR1 &= CR1_OPM_Reset;
+
+ /* Configure the OPM Mode */
+ TIMx->CR1 |= TIM_OPMode;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectOutputTrigger
+* Description : Selects the TIMx Trigger Output Mode.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_TRGOSource: specifies the Trigger Output source.
+* This paramter can be as follow:
+* 1/ For TIM1 to TIM8:
+* - TIM_TRGOSource_Reset
+* - TIM_TRGOSource_Enable
+* - TIM_TRGOSource_Update
+* 2/ These parameters are available for all TIMx except
+* TIM6 and TIM7:
+* - TIM_TRGOSource_OC1
+* - TIM_TRGOSource_OC1Ref
+* - TIM_TRGOSource_OC2Ref
+* - TIM_TRGOSource_OC3Ref
+* - TIM_TRGOSource_OC4Ref
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, u16 TIM_TRGOSource)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_TRGO_SOURCE(TIM_TRGOSource));
+ assert_param(IS_TIM_PERIPH_TRGO(TIMx, TIM_TRGOSource));
+
+ /* Reset the MMS Bits */
+ TIMx->CR2 &= CR2_MMS_Mask;
+
+ /* Select the TRGO source */
+ TIMx->CR2 |= TIM_TRGOSource;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectSlaveMode
+* Description : Selects the TIMx Slave Mode.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_SlaveMode: specifies the Timer Slave Mode.
+* This paramter can be one of the following values:
+* - TIM_SlaveMode_Reset
+* - TIM_SlaveMode_Gated
+* - TIM_SlaveMode_Trigger
+* - TIM_SlaveMode_External1
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, u16 TIM_SlaveMode)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_SLAVE_MODE(TIM_SlaveMode));
+
+ /* Reset the SMS Bits */
+ TIMx->SMCR &= SMCR_SMS_Mask;
+
+ /* Select the Slave Mode */
+ TIMx->SMCR |= TIM_SlaveMode;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SelectMasterSlaveMode
+* Description : Sets or Resets the TIMx Master/Slave Mode.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_MasterSlaveMode: specifies the Timer Master Slave Mode.
+* This paramter can be one of the following values:
+* - TIM_MasterSlaveMode_Enable: synchronization between the
+* current timer and its slaves (through TRGO).
+* - TIM_MasterSlaveMode_Disable: No action
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, u16 TIM_MasterSlaveMode)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_MSM_STATE(TIM_MasterSlaveMode));
+
+ /* Reset the MSM Bit */
+ TIMx->SMCR &= SMCR_MSM_Reset;
+
+ /* Set or Reset the MSM Bit */
+ TIMx->SMCR |= TIM_MasterSlaveMode;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetCounter
+* Description : Sets the TIMx Counter Register value
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - Counter: specifies the Counter register new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetCounter(TIM_TypeDef* TIMx, u16 Counter)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+
+ /* Set the Counter Register value */
+ TIMx->CNT = Counter;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetAutoreload
+* Description : Sets the TIMx Autoreload Register value
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - Autoreload: specifies the Autoreload register new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetAutoreload(TIM_TypeDef* TIMx, u16 Autoreload)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+
+ /* Set the Autoreload Register value */
+ TIMx->ARR = Autoreload;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetCompare1
+* Description : Sets the TIMx Capture Compare1 Register value
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - Compare1: specifies the Capture Compare1 register new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetCompare1(TIM_TypeDef* TIMx, u16 Compare1)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Set the Capture Compare1 Register value */
+ TIMx->CCR1 = Compare1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetCompare2
+* Description : Sets the TIMx Capture Compare2 Register value
+* Input : TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - Compare2: specifies the Capture Compare2 register new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetCompare2(TIM_TypeDef* TIMx, u16 Compare2)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Set the Capture Compare2 Register value */
+ TIMx->CCR2 = Compare2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetCompare3
+* Description : Sets the TIMx Capture Compare3 Register value
+* Input : TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - Compare3: specifies the Capture Compare3 register new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetCompare3(TIM_TypeDef* TIMx, u16 Compare3)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Set the Capture Compare3 Register value */
+ TIMx->CCR3 = Compare3;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetCompare4
+* Description : Sets the TIMx Capture Compare4 Register value
+* Input : TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - Compare4: specifies the Capture Compare4 register new value.
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetCompare4(TIM_TypeDef* TIMx, u16 Compare4)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Set the Capture Compare4 Register value */
+ TIMx->CCR4 = Compare4;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetIC1Prescaler
+* Description : Sets the TIMx Input Capture 1 prescaler.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPSC: specifies the Input Capture1 prescaler
+* new value.
+* This parameter can be one of the following values:
+* - TIM_ICPSC_DIV1: no prescaler
+* - TIM_ICPSC_DIV2: capture is done once every 2 events
+* - TIM_ICPSC_DIV4: capture is done once every 4 events
+* - TIM_ICPSC_DIV8: capture is done once every 8 events
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+
+ /* Reset the IC1PSC Bits */
+ TIMx->CCMR1 &= CCMR_IC13PSC_Mask;
+
+ /* Set the IC1PSC value */
+ TIMx->CCMR1 |= TIM_ICPSC;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetIC2Prescaler
+* Description : Sets the TIMx Input Capture 2 prescaler.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPSC: specifies the Input Capture2 prescaler
+* new value.
+* This parameter can be one of the following values:
+* - TIM_ICPSC_DIV1: no prescaler
+* - TIM_ICPSC_DIV2: capture is done once every 2 events
+* - TIM_ICPSC_DIV4: capture is done once every 4 events
+* - TIM_ICPSC_DIV8: capture is done once every 8 events
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+
+ /* Reset the IC2PSC Bits */
+ TIMx->CCMR1 &= CCMR_IC24PSC_Mask;
+
+ /* Set the IC2PSC value */
+ TIMx->CCMR1 |= (u16)(TIM_ICPSC << 8);
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetIC3Prescaler
+* Description : Sets the TIMx Input Capture 3 prescaler.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPSC: specifies the Input Capture3 prescaler
+* new value.
+* This parameter can be one of the following values:
+* - TIM_ICPSC_DIV1: no prescaler
+* - TIM_ICPSC_DIV2: capture is done once every 2 events
+* - TIM_ICPSC_DIV4: capture is done once every 4 events
+* - TIM_ICPSC_DIV8: capture is done once every 8 events
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+
+ /* Reset the IC3PSC Bits */
+ TIMx->CCMR2 &= CCMR_IC13PSC_Mask;
+
+ /* Set the IC3PSC value */
+ TIMx->CCMR2 |= TIM_ICPSC;
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetIC4Prescaler
+* Description : Sets the TIMx Input Capture 4 prescaler.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPSC: specifies the Input Capture4 prescaler
+* new value.
+* This parameter can be one of the following values:
+* - TIM_ICPSC_DIV1: no prescaler
+* - TIM_ICPSC_DIV2: capture is done once every 2 events
+* - TIM_ICPSC_DIV4: capture is done once every 4 events
+* - TIM_ICPSC_DIV8: capture is done once every 8 events
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, u16 TIM_ICPSC)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+
+ /* Reset the IC4PSC Bits */
+ TIMx->CCMR2 &= CCMR_IC24PSC_Mask;
+
+ /* Set the IC4PSC value */
+ TIMx->CCMR2 |= (u16)(TIM_ICPSC << 8);
+}
+
+/*******************************************************************************
+* Function Name : TIM_SetClockDivision
+* Description : Sets the TIMx Clock Division value.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_CKD: specifies the clock division value.
+* This parameter can be one of the following value:
+* - TIM_CKD_DIV1: TDTS = Tck_tim
+* - TIM_CKD_DIV2: TDTS = 2*Tck_tim
+* - TIM_CKD_DIV4: TDTS = 4*Tck_tim
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_SetClockDivision(TIM_TypeDef* TIMx, u16 TIM_CKD)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+ assert_param(IS_TIM_CKD_DIV(TIM_CKD));
+
+ /* Reset the CKD Bits */
+ TIMx->CR1 &= CR1_CKD_Mask;
+
+ /* Set the CKD value */
+ TIMx->CR1 |= TIM_CKD;
+}
+/*******************************************************************************
+* Function Name : TIM_GetCapture1
+* Description : Gets the TIMx Input Capture 1 value.
+* Input : TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* Output : None
+* Return : Capture Compare 1 Register value.
+*******************************************************************************/
+u16 TIM_GetCapture1(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Get the Capture 1 Register value */
+ return TIMx->CCR1;
+}
+
+/*******************************************************************************
+* Function Name : TIM_GetCapture2
+* Description : Gets the TIMx Input Capture 2 value.
+* Input : TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* Output : None
+* Return : Capture Compare 2 Register value.
+*******************************************************************************/
+u16 TIM_GetCapture2(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Get the Capture 2 Register value */
+ return TIMx->CCR2;
+}
+
+/*******************************************************************************
+* Function Name : TIM_GetCapture3
+* Description : Gets the TIMx Input Capture 3 value.
+* Input : TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* Output : None
+* Return : Capture Compare 3 Register value.
+*******************************************************************************/
+u16 TIM_GetCapture3(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Get the Capture 3 Register value */
+ return TIMx->CCR3;
+}
+
+/*******************************************************************************
+* Function Name : TIM_GetCapture4
+* Description : Gets the TIMx Input Capture 4 value.
+* Input : TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* Output : None
+* Return : Capture Compare 4 Register value.
+*******************************************************************************/
+u16 TIM_GetCapture4(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_123458_PERIPH(TIMx));
+
+ /* Get the Capture 4 Register value */
+ return TIMx->CCR4;
+}
+
+/*******************************************************************************
+* Function Name : TIM_GetCounter
+* Description : Gets the TIMx Counter value.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* Output : None
+* Return : Counter Register value.
+*******************************************************************************/
+u16 TIM_GetCounter(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+
+ /* Get the Counter Register value */
+ return TIMx->CNT;
+}
+
+/*******************************************************************************
+* Function Name : TIM_GetPrescaler
+* Description : Gets the TIMx Prescaler value.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* Output : None
+* Return : Prescaler Register value.
+*******************************************************************************/
+u16 TIM_GetPrescaler(TIM_TypeDef* TIMx)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+
+ /* Get the Prescaler Register value */
+ return TIMx->PSC;
+}
+
+/*******************************************************************************
+* Function Name : TIM_GetFlagStatus
+* Description : Checks whether the specified TIM flag is set or not.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - TIM_FLAG_Update: TIM update Flag
+* - TIM_FLAG_CC1: TIM Capture Compare 1 Flag
+* - TIM_FLAG_CC2: TIM Capture Compare 2 Flag
+* - TIM_FLAG_CC3: TIM Capture Compare 3 Flag
+* - TIM_FLAG_CC4: TIM Capture Compare 4 Flag
+* - TIM_FLAG_COM: TIM Commutation Flag
+* - TIM_FLAG_Trigger: TIM Trigger Flag
+* - TIM_FLAG_Break: TIM Break Flag
+* - TIM_FLAG_CC1OF: TIM Capture Compare 1 overcapture Flag
+* - TIM_FLAG_CC2OF: TIM Capture Compare 2 overcapture Flag
+* - TIM_FLAG_CC3OF: TIM Capture Compare 3 overcapture Flag
+* - TIM_FLAG_CC4OF: TIM Capture Compare 4 overcapture Flag
+* Output : None
+* Return : The new state of TIM_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, u16 TIM_FLAG)
+{
+ ITStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_GET_FLAG(TIM_FLAG));
+ assert_param(IS_TIM_PERIPH_FLAG(TIMx, TIM_FLAG));
+
+ if ((TIMx->SR & TIM_FLAG) != (u16)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ClearFlag
+* Description : Clears the TIMx's pending flags.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_FLAG: specifies the flag bit to clear.
+* This parameter can be any combination of the following values:
+* - TIM_FLAG_Update: TIM update Flag
+* - TIM_FLAG_CC1: TIM Capture Compare 1 Flag
+* - TIM_FLAG_CC2: TIM Capture Compare 2 Flag
+* - TIM_FLAG_CC3: TIM Capture Compare 3 Flag
+* - TIM_FLAG_CC4: TIM Capture Compare 4 Flag
+* - TIM_FLAG_COM: TIM Commutation Flag
+* - TIM_FLAG_Trigger: TIM Trigger Flag
+* - TIM_FLAG_Break: TIM Break Flag
+* - TIM_FLAG_CC1OF: TIM Capture Compare 1 overcapture Flag
+* - TIM_FLAG_CC2OF: TIM Capture Compare 2 overcapture Flag
+* - TIM_FLAG_CC3OF: TIM Capture Compare 3 overcapture Flag
+* - TIM_FLAG_CC4OF: TIM Capture Compare 4 overcapture Flag
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ClearFlag(TIM_TypeDef* TIMx, u16 TIM_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_CLEAR_FLAG(TIMx, TIM_FLAG));
+
+ /* Clear the flags */
+ TIMx->SR = (u16)~TIM_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : TIM_GetITStatus
+* Description : Checks whether the TIM interrupt has occurred or not.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_IT: specifies the TIM interrupt source to check.
+* This parameter can be one of the following values:
+* - TIM_IT_Update: TIM update Interrupt source
+* - TIM_IT_CC1: TIM Capture Compare 1 Interrupt source
+* - TIM_IT_CC2: TIM Capture Compare 2 Interrupt source
+* - TIM_IT_CC3: TIM Capture Compare 3 Interrupt source
+* - TIM_IT_CC4: TIM Capture Compare 4 Interrupt source
+* - TIM_IT_COM: TIM Commutation Interrupt
+* source
+* - TIM_IT_Trigger: TIM Trigger Interrupt source
+* - TIM_IT_Break: TIM Break Interrupt source
+* Output : None
+* Return : The new state of the TIM_IT(SET or RESET).
+*******************************************************************************/
+ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, u16 TIM_IT)
+{
+ ITStatus bitstatus = RESET;
+ u16 itstatus = 0x0, itenable = 0x0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_GET_IT(TIM_IT));
+ assert_param(IS_TIM_PERIPH_IT(TIMx, TIM_IT));
+
+ itstatus = TIMx->SR & TIM_IT;
+
+ itenable = TIMx->DIER & TIM_IT;
+
+ if ((itstatus != (u16)RESET) && (itenable != (u16)RESET))
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : TIM_ClearITPendingBit
+* Description : Clears the TIMx's interrupt pending bits.
+* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
+* - TIM_IT: specifies the pending bit to clear.
+* This parameter can be any combination of the following values:
+* - TIM_IT_Update: TIM1 update Interrupt source
+* - TIM_IT_CC1: TIM Capture Compare 1 Interrupt source
+* - TIM_IT_CC2: TIM Capture Compare 2 Interrupt source
+* - TIM_IT_CC3: TIM Capture Compare 3 Interrupt source
+* - TIM_IT_CC4: TIM Capture Compare 4 Interrupt source
+* - TIM_IT_COM: TIM Commutation Interrupt
+* source
+* - TIM_IT_Trigger: TIM Trigger Interrupt source
+* - TIM_IT_Break: TIM Break Interrupt source
+* Output : None
+* Return : None
+*******************************************************************************/
+void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, u16 TIM_IT)
+{
+ /* Check the parameters */
+ assert_param(IS_TIM_ALL_PERIPH(TIMx));
+ assert_param(IS_TIM_PERIPH_IT(TIMx, TIM_IT));
+
+ /* Clear the IT pending Bit */
+ TIMx->SR = (u16)~TIM_IT;
+}
+
+/*******************************************************************************
+* Function Name : TI1_Config
+* Description : Configure the TI1 as Input.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPolarity : The Input Polarity.
+* This parameter can be one of the following values:
+* - TIM_ICPolarity_Rising
+* - TIM_ICPolarity_Falling
+* - TIM_ICSelection: specifies the input to be used.
+* This parameter can be one of the following values:
+* - TIM_ICSelection_DirectTI: TIM Input 1 is selected to
+* be connected to IC1.
+* - TIM_ICSelection_IndirectTI: TIM Input 1 is selected to
+* be connected to IC2.
+* - TIM_ICSelection_TRC: TIM Input 1 is selected to be
+* connected to TRC.
+* - TIM_ICFilter: Specifies the Input Capture Filter.
+* This parameter must be a value between 0x00 and 0x0F.
+* Output : None
+* Return : None
+*******************************************************************************/
+static void TI1_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter)
+{
+ u16 tmpccmr1 = 0, tmpccer = 0;
+
+ /* Disable the Channel 1: Reset the CC1E Bit */
+ TIMx->CCER &= CCER_CC1E_Reset;
+
+ tmpccmr1 = TIMx->CCMR1;
+ tmpccer = TIMx->CCER;
+
+ /* Select the Input and set the filter */
+ tmpccmr1 &= CCMR_CC13S_Mask & CCMR_IC13F_Mask;
+ tmpccmr1 |= TIM_ICSelection | (u16)(TIM_ICFilter << 4);
+
+ /* Select the Polarity and set the CC1E Bit */
+ tmpccer &= CCER_CC1P_Reset;
+ tmpccer |= TIM_ICPolarity | CCER_CC1E_Set;
+
+ /* Write to TIMx CCMR1 and CCER registers */
+ TIMx->CCMR1 = tmpccmr1;
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TI2_Config
+* Description : Configure the TI2 as Input.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPolarity : The Input Polarity.
+* This parameter can be one of the following values:
+* - TIM_ICPolarity_Rising
+* - TIM_ICPolarity_Falling
+* - TIM_ICSelection: specifies the input to be used.
+* This parameter can be one of the following values:
+* - TIM_ICSelection_DirectTI: TIM Input 2 is selected to
+* be connected to IC2.
+* - TIM_ICSelection_IndirectTI: TIM Input 2 is selected to
+* be connected to IC1.
+* - TIM_ICSelection_TRC: TIM Input 2 is selected to be
+* connected to TRC.
+* - TIM_ICFilter: Specifies the Input Capture Filter.
+* This parameter must be a value between 0x00 and 0x0F.
+* Output : None
+* Return : None
+*******************************************************************************/
+static void TI2_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter)
+{
+ u16 tmpccmr1 = 0, tmpccer = 0, tmp = 0;
+
+ /* Disable the Channel 2: Reset the CC2E Bit */
+ TIMx->CCER &= CCER_CC2E_Reset;
+
+ tmpccmr1 = TIMx->CCMR1;
+ tmpccer = TIMx->CCER;
+ tmp = (u16)(TIM_ICPolarity << 4);
+
+ /* Select the Input and set the filter */
+ tmpccmr1 &= CCMR_CC24S_Mask & CCMR_IC24F_Mask;
+ tmpccmr1 |= (u16)(TIM_ICFilter << 12);
+ tmpccmr1 |= (u16)(TIM_ICSelection << 8);
+
+ /* Select the Polarity and set the CC2E Bit */
+ tmpccer &= CCER_CC2P_Reset;
+ tmpccer |= tmp | CCER_CC2E_Set;
+
+ /* Write to TIMx CCMR1 and CCER registers */
+ TIMx->CCMR1 = tmpccmr1 ;
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TI3_Config
+* Description : Configure the TI3 as Input.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPolarity : The Input Polarity.
+* This parameter can be one of the following values:
+* - TIM_ICPolarity_Rising
+* - TIM_ICPolarity_Falling
+* - TIM_ICSelection: specifies the input to be used.
+* This parameter can be one of the following values:
+* - TIM_ICSelection_DirectTI: TIM Input 3 is selected to
+* be connected to IC3.
+* - TIM_ICSelection_IndirectTI: TIM Input 3 is selected to
+* be connected to IC4.
+* - TIM_ICSelection_TRC: TIM Input 3 is selected to be
+* connected to TRC.
+* - TIM_ICFilter: Specifies the Input Capture Filter.
+* This parameter must be a value between 0x00 and 0x0F.
+* Output : None
+* Return : None
+*******************************************************************************/
+static void TI3_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter)
+{
+ u16 tmpccmr2 = 0, tmpccer = 0, tmp = 0;
+
+ /* Disable the Channel 3: Reset the CC3E Bit */
+ TIMx->CCER &= CCER_CC3E_Reset;
+
+ tmpccmr2 = TIMx->CCMR2;
+ tmpccer = TIMx->CCER;
+ tmp = (u16)(TIM_ICPolarity << 8);
+
+ /* Select the Input and set the filter */
+ tmpccmr2 &= CCMR_CC13S_Mask & CCMR_IC13F_Mask;
+ tmpccmr2 |= TIM_ICSelection | (u16)(TIM_ICFilter << 4);
+
+ /* Select the Polarity and set the CC3E Bit */
+ tmpccer &= CCER_CC3P_Reset;
+ tmpccer |= tmp | CCER_CC3E_Set;
+
+ /* Write to TIMx CCMR2 and CCER registers */
+ TIMx->CCMR2 = tmpccmr2;
+ TIMx->CCER = tmpccer;
+}
+
+/*******************************************************************************
+* Function Name : TI4_Config
+* Description : Configure the TI1 as Input.
+* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
+* peripheral.
+* - TIM_ICPolarity : The Input Polarity.
+* This parameter can be one of the following values:
+* - TIM_ICPolarity_Rising
+* - TIM_ICPolarity_Falling
+* - TIM_ICSelection: specifies the input to be used.
+* This parameter can be one of the following values:
+* - TIM_ICSelection_DirectTI: TIM Input 4 is selected to
+* be connected to IC4.
+* - TIM_ICSelection_IndirectTI: TIM Input 4 is selected to
+* be connected to IC3.
+* - TIM_ICSelection_TRC: TIM Input 4 is selected to be
+* connected to TRC.
+* - TIM_ICFilter: Specifies the Input Capture Filter.
+* This parameter must be a value between 0x00 and 0x0F.
+* Output : None
+* Return : None
+*******************************************************************************/
+static void TI4_Config(TIM_TypeDef* TIMx, u16 TIM_ICPolarity, u16 TIM_ICSelection,
+ u16 TIM_ICFilter)
+{
+ u16 tmpccmr2 = 0, tmpccer = 0, tmp = 0;
+
+ /* Disable the Channel 4: Reset the CC4E Bit */
+ TIMx->CCER &= CCER_CC4E_Reset;
+
+ tmpccmr2 = TIMx->CCMR2;
+ tmpccer = TIMx->CCER;
+ tmp = (u16)(TIM_ICPolarity << 12);
+
+ /* Select the Input and set the filter */
+ tmpccmr2 &= CCMR_CC24S_Mask & CCMR_IC24F_Mask;
+ tmpccmr2 |= (u16)(TIM_ICSelection << 8) | (u16)(TIM_ICFilter << 12);
+
+ /* Select the Polarity and set the CC4E Bit */
+ tmpccer &= CCER_CC4P_Reset;
+ tmpccer |= tmp | CCER_CC4E_Set;
+
+ /* Write to TIMx CCMR2 and CCER registers */
+ TIMx->CCMR2 = tmpccmr2;
+ TIMx->CCER = tmpccer ;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_usart.c b/src/stm32lib/src/stm32f10x_usart.c new file mode 100644 index 0000000..baf9c47 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_usart.c @@ -0,0 +1,1001 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_usart.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the USART firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_usart.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* USART UE Mask */
+#define CR1_UE_Set ((u16)0x2000) /* USART Enable Mask */
+#define CR1_UE_Reset ((u16)0xDFFF) /* USART Disable Mask */
+
+/* USART WakeUp Method */
+#define CR1_WAKE_Mask ((u16)0xF7FF) /* USART WakeUp Method Mask */
+
+/* USART RWU Mask */
+#define CR1_RWU_Set ((u16)0x0002) /* USART mute mode Enable Mask */
+#define CR1_RWU_Reset ((u16)0xFFFD) /* USART mute mode Enable Mask */
+
+#define CR1_SBK_Set ((u16)0x0001) /* USART Break Character send Mask */
+
+#define CR1_CLEAR_Mask ((u16)0xE9F3) /* USART CR1 Mask */
+
+#define CR2_Address_Mask ((u16)0xFFF0) /* USART address Mask */
+
+/* USART LIN Mask */
+#define CR2_LINEN_Set ((u16)0x4000) /* USART LIN Enable Mask */
+#define CR2_LINEN_Reset ((u16)0xBFFF) /* USART LIN Disable Mask */
+
+/* USART LIN Break detection */
+#define CR2_LBDL_Mask ((u16)0xFFDF) /* USART LIN Break detection Mask */
+
+#define CR2_STOP_CLEAR_Mask ((u16)0xCFFF) /* USART CR2 STOP Bits Mask */
+#define CR2_CLOCK_CLEAR_Mask ((u16)0xF0FF) /* USART CR2 Clock Mask */
+
+/* USART SC Mask */
+#define CR3_SCEN_Set ((u16)0x0020) /* USART SC Enable Mask */
+#define CR3_SCEN_Reset ((u16)0xFFDF) /* USART SC Disable Mask */
+
+/* USART SC NACK Mask */
+#define CR3_NACK_Set ((u16)0x0010) /* USART SC NACK Enable Mask */
+#define CR3_NACK_Reset ((u16)0xFFEF) /* USART SC NACK Disable Mask */
+
+/* USART Half-Duplex Mask */
+#define CR3_HDSEL_Set ((u16)0x0008) /* USART Half-Duplex Enable Mask */
+#define CR3_HDSEL_Reset ((u16)0xFFF7) /* USART Half-Duplex Disable Mask */
+
+/* USART IrDA Mask */
+#define CR3_IRLP_Mask ((u16)0xFFFB) /* USART IrDA LowPower mode Mask */
+
+#define CR3_CLEAR_Mask ((u16)0xFCFF) /* USART CR3 Mask */
+
+/* USART IrDA Mask */
+#define CR3_IREN_Set ((u16)0x0002) /* USART IrDA Enable Mask */
+#define CR3_IREN_Reset ((u16)0xFFFD) /* USART IrDA Disable Mask */
+
+#define GTPR_LSB_Mask ((u16)0x00FF) /* Guard Time Register LSB Mask */
+#define GTPR_MSB_Mask ((u16)0xFF00) /* Guard Time Register MSB Mask */
+
+#define IT_Mask ((u16)0x001F) /* USART Interrupt Mask */
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : USART_DeInit
+* Description : Deinitializes the USARTx peripheral registers to their
+* default reset values.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_DeInit(USART_TypeDef* USARTx)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+
+ switch (*(u32*)&USARTx)
+ {
+ case USART1_BASE:
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, ENABLE);
+ RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, DISABLE);
+ break;
+
+ case USART2_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, DISABLE);
+ break;
+
+ case USART3_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, DISABLE);
+ break;
+
+ case UART4_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, DISABLE);
+ break;
+
+ case UART5_BASE:
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, DISABLE);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_Init
+* Description : Initializes the USARTx peripheral according to the specified
+* parameters in the USART_InitStruct .
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_InitStruct: pointer to a USART_InitTypeDef structure
+* that contains the configuration information for the
+* specified USART peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct)
+{
+ u32 tmpreg = 0x00, apbclock = 0x00;
+ u32 integerdivider = 0x00;
+ u32 fractionaldivider = 0x00;
+ u32 usartxbase = 0;
+ RCC_ClocksTypeDef RCC_ClocksStatus;
+
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_BAUDRATE(USART_InitStruct->USART_BaudRate));
+ assert_param(IS_USART_WORD_LENGTH(USART_InitStruct->USART_WordLength));
+ assert_param(IS_USART_STOPBITS(USART_InitStruct->USART_StopBits));
+ assert_param(IS_USART_PARITY(USART_InitStruct->USART_Parity));
+ assert_param(IS_USART_MODE(USART_InitStruct->USART_Mode));
+ assert_param(IS_USART_HARDWARE_FLOW_CONTROL(USART_InitStruct->USART_HardwareFlowControl));
+ /* The hardware flow control is available only for USART1, USART2 and USART3 */
+ assert_param(IS_USART_PERIPH_HFC(USARTx, USART_InitStruct->USART_HardwareFlowControl));
+
+ usartxbase = (*(u32*)&USARTx);
+
+/*---------------------------- USART CR2 Configuration -----------------------*/
+ tmpreg = USARTx->CR2;
+ /* Clear STOP[13:12] bits */
+ tmpreg &= CR2_STOP_CLEAR_Mask;
+
+ /* Configure the USART Stop Bits, Clock, CPOL, CPHA and LastBit ------------*/
+ /* Set STOP[13:12] bits according to USART_StopBits value */
+ tmpreg |= (u32)USART_InitStruct->USART_StopBits;
+
+ /* Write to USART CR2 */
+ USARTx->CR2 = (u16)tmpreg;
+
+/*---------------------------- USART CR1 Configuration -----------------------*/
+ tmpreg = USARTx->CR1;
+ /* Clear M, PCE, PS, TE and RE bits */
+ tmpreg &= CR1_CLEAR_Mask;
+
+ /* Configure the USART Word Length, Parity and mode ----------------------- */
+ /* Set the M bits according to USART_WordLength value */
+ /* Set PCE and PS bits according to USART_Parity value */
+ /* Set TE and RE bits according to USART_Mode value */
+ tmpreg |= (u32)USART_InitStruct->USART_WordLength | USART_InitStruct->USART_Parity |
+ USART_InitStruct->USART_Mode;
+
+ /* Write to USART CR1 */
+ USARTx->CR1 = (u16)tmpreg;
+
+/*---------------------------- USART CR3 Configuration -----------------------*/
+ tmpreg = USARTx->CR3;
+ /* Clear CTSE and RTSE bits */
+ tmpreg &= CR3_CLEAR_Mask;
+
+ /* Configure the USART HFC -------------------------------------------------*/
+ /* Set CTSE and RTSE bits according to USART_HardwareFlowControl value */
+ tmpreg |= USART_InitStruct->USART_HardwareFlowControl;
+
+ /* Write to USART CR3 */
+ USARTx->CR3 = (u16)tmpreg;
+
+/*---------------------------- USART BRR Configuration -----------------------*/
+ /* Configure the USART Baud Rate -------------------------------------------*/
+ RCC_GetClocksFreq(&RCC_ClocksStatus);
+ if (usartxbase == USART1_BASE)
+ {
+ apbclock = RCC_ClocksStatus.PCLK2_Frequency;
+ }
+ else
+ {
+ apbclock = RCC_ClocksStatus.PCLK1_Frequency;
+ }
+
+ /* Determine the integer part */
+ integerdivider = ((0x19 * apbclock) / (0x04 * (USART_InitStruct->USART_BaudRate)));
+ tmpreg = (integerdivider / 0x64) << 0x04;
+
+ /* Determine the fractional part */
+ fractionaldivider = integerdivider - (0x64 * (tmpreg >> 0x04));
+ tmpreg |= ((((fractionaldivider * 0x10) + 0x32) / 0x64)) & ((u8)0x0F);
+
+ /* Write to USART BRR */
+ USARTx->BRR = (u16)tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : USART_StructInit
+* Description : Fills each USART_InitStruct member with its default value.
+* Input : - USART_InitStruct: pointer to a USART_InitTypeDef structure
+* which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_StructInit(USART_InitTypeDef* USART_InitStruct)
+{
+ /* USART_InitStruct members default value */
+ USART_InitStruct->USART_BaudRate = 9600;
+ USART_InitStruct->USART_WordLength = USART_WordLength_8b;
+ USART_InitStruct->USART_StopBits = USART_StopBits_1;
+ USART_InitStruct->USART_Parity = USART_Parity_No ;
+ USART_InitStruct->USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+ USART_InitStruct->USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+}
+
+/*******************************************************************************
+* Function Name : USART_ClockInit
+* Description : Initializes the USARTx peripheral Clock according to the
+* specified parameters in the USART_ClockInitStruct .
+* Input : - USARTx: where x can be 1, 2, 3 to select the USART peripheral.
+* Note: The Smart Card mode is not available for UART4 and UART5.
+* - USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef
+* structure that contains the configuration information for
+* the specified USART peripheral.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct)
+{
+ u32 tmpreg = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_USART_123_PERIPH(USARTx));
+ assert_param(IS_USART_CLOCK(USART_ClockInitStruct->USART_Clock));
+ assert_param(IS_USART_CPOL(USART_ClockInitStruct->USART_CPOL));
+ assert_param(IS_USART_CPHA(USART_ClockInitStruct->USART_CPHA));
+ assert_param(IS_USART_LASTBIT(USART_ClockInitStruct->USART_LastBit));
+
+/*---------------------------- USART CR2 Configuration -----------------------*/
+ tmpreg = USARTx->CR2;
+ /* Clear CLKEN, CPOL, CPHA and LBCL bits */
+ tmpreg &= CR2_CLOCK_CLEAR_Mask;
+
+ /* Configure the USART Clock, CPOL, CPHA and LastBit ------------*/
+ /* Set CLKEN bit according to USART_Clock value */
+ /* Set CPOL bit according to USART_CPOL value */
+ /* Set CPHA bit according to USART_CPHA value */
+ /* Set LBCL bit according to USART_LastBit value */
+ tmpreg |= (u32)USART_ClockInitStruct->USART_Clock | USART_ClockInitStruct->USART_CPOL |
+ USART_ClockInitStruct->USART_CPHA | USART_ClockInitStruct->USART_LastBit;
+
+ /* Write to USART CR2 */
+ USARTx->CR2 = (u16)tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : USART_ClockStructInit
+* Description : Fills each USART_ClockInitStruct member with its default value.
+* Input : - USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef
+* structure which will be initialized.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct)
+{
+ /* USART_ClockInitStruct members default value */
+ USART_ClockInitStruct->USART_Clock = USART_Clock_Disable;
+ USART_ClockInitStruct->USART_CPOL = USART_CPOL_Low;
+ USART_ClockInitStruct->USART_CPHA = USART_CPHA_1Edge;
+ USART_ClockInitStruct->USART_LastBit = USART_LastBit_Disable;
+}
+
+/*******************************************************************************
+* Function Name : USART_Cmd
+* Description : Enables or disables the specified USART peripheral.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* : - NewState: new state of the USARTx peripheral.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the selected USART by setting the UE bit in the CR1 register */
+ USARTx->CR1 |= CR1_UE_Set;
+ }
+ else
+ {
+ /* Disable the selected USART by clearing the UE bit in the CR1 register */
+ USARTx->CR1 &= CR1_UE_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_ITConfig
+* Description : Enables or disables the specified USART interrupts.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_IT: specifies the USART interrupt sources to be
+* enabled or disabled.
+* This parameter can be one of the following values:
+* - USART_IT_CTS: CTS change interrupt (not available for
+* UART4 and UART5)
+* - USART_IT_LBD: LIN Break detection interrupt
+* - USART_IT_TXE: Tansmit Data Register empty interrupt
+* - USART_IT_TC: Transmission complete interrupt
+* - USART_IT_RXNE: Receive Data register not empty
+* interrupt
+* - USART_IT_IDLE: Idle line detection interrupt
+* - USART_IT_PE: Parity Error interrupt
+* - USART_IT_ERR: Error interrupt(Frame error, noise
+* error, overrun error)
+* - NewState: new state of the specified USARTx interrupts.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_ITConfig(USART_TypeDef* USARTx, u16 USART_IT, FunctionalState NewState)
+{
+ u32 usartreg = 0x00, itpos = 0x00, itmask = 0x00;
+ u32 usartxbase = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_CONFIG_IT(USART_IT));
+ assert_param(IS_USART_PERIPH_IT(USARTx, USART_IT)); /* The CTS interrupt is not available for UART4 and UART5 */
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ usartxbase = (*(u32*)&(USARTx));
+
+ /* Get the USART register index */
+ usartreg = (((u8)USART_IT) >> 0x05);
+
+ /* Get the interrupt position */
+ itpos = USART_IT & IT_Mask;
+
+ itmask = (((u32)0x01) << itpos);
+
+ if (usartreg == 0x01) /* The IT is in CR1 register */
+ {
+ usartxbase += 0x0C;
+ }
+ else if (usartreg == 0x02) /* The IT is in CR2 register */
+ {
+ usartxbase += 0x10;
+ }
+ else /* The IT is in CR3 register */
+ {
+ usartxbase += 0x14;
+ }
+ if (NewState != DISABLE)
+ {
+ *(vu32*)usartxbase |= itmask;
+ }
+ else
+ {
+ *(vu32*)usartxbase &= ~itmask;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_DMACmd
+* Description : Enables or disables the USART’s DMA interface.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3 or UART4.
+* Note: The DMA mode is not available for UART5.
+* - USART_DMAReq: specifies the DMA request.
+* This parameter can be any combination of the following values:
+* - USART_DMAReq_Tx: USART DMA transmit request
+* - USART_DMAReq_Rx: USART DMA receive request
+* - NewState: new state of the DMA Request sources.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_DMACmd(USART_TypeDef* USARTx, u16 USART_DMAReq, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_1234_PERIPH(USARTx));
+ assert_param(IS_USART_DMAREQ(USART_DMAReq));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the DMA transfer for selected requests by setting the DMAT and/or
+ DMAR bits in the USART CR3 register */
+ USARTx->CR3 |= USART_DMAReq;
+ }
+ else
+ {
+ /* Disable the DMA transfer for selected requests by clearing the DMAT and/or
+ DMAR bits in the USART CR3 register */
+ USARTx->CR3 &= (u16)~USART_DMAReq;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_SetAddress
+* Description : Sets the address of the USART node.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_Address: Indicates the address of the USART node.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_SetAddress(USART_TypeDef* USARTx, u8 USART_Address)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_ADDRESS(USART_Address));
+
+ /* Clear the USART address */
+ USARTx->CR2 &= CR2_Address_Mask;
+ /* Set the USART address node */
+ USARTx->CR2 |= USART_Address;
+}
+
+/*******************************************************************************
+* Function Name : USART_WakeUpConfig
+* Description : Selects the USART WakeUp method.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_WakeUp: specifies the USART wakeup method.
+* This parameter can be one of the following values:
+* - USART_WakeUp_IdleLine: WakeUp by an idle line detection
+* - USART_WakeUp_AddressMark: WakeUp by an address mark
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_WakeUpConfig(USART_TypeDef* USARTx, u16 USART_WakeUp)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_WAKEUP(USART_WakeUp));
+
+ USARTx->CR1 &= CR1_WAKE_Mask;
+ USARTx->CR1 |= USART_WakeUp;
+}
+
+/*******************************************************************************
+* Function Name : USART_ReceiverWakeUpCmd
+* Description : Determines if the USART is in mute mode or not.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - NewState: new state of the USART mute mode.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the USART mute mode by setting the RWU bit in the CR1 register */
+ USARTx->CR1 |= CR1_RWU_Set;
+ }
+ else
+ {
+ /* Disable the USART mute mode by clearing the RWU bit in the CR1 register */
+ USARTx->CR1 &= CR1_RWU_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_LINBreakDetectLengthConfig
+* Description : Sets the USART LIN Break detection length.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_LINBreakDetectLength: specifies the LIN break
+* detection length.
+* This parameter can be one of the following values:
+* - USART_LINBreakDetectLength_10b: 10-bit break detection
+* - USART_LINBreakDetectLength_11b: 11-bit break detection
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, u16 USART_LINBreakDetectLength)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_LIN_BREAK_DETECT_LENGTH(USART_LINBreakDetectLength));
+
+ USARTx->CR2 &= CR2_LBDL_Mask;
+ USARTx->CR2 |= USART_LINBreakDetectLength;
+}
+
+/*******************************************************************************
+* Function Name : USART_LINCmd
+* Description : Enables or disables the USART’s LIN mode.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - NewState: new state of the USART LIN mode.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the LIN mode by setting the LINEN bit in the CR2 register */
+ USARTx->CR2 |= CR2_LINEN_Set;
+ }
+ else
+ {
+ /* Disable the LIN mode by clearing the LINEN bit in the CR2 register */
+ USARTx->CR2 &= CR2_LINEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_SendData
+* Description : Transmits single data through the USARTx peripheral.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - Data: the data to transmit.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_SendData(USART_TypeDef* USARTx, u16 Data)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_DATA(Data));
+
+ /* Transmit Data */
+ USARTx->DR = (Data & (u16)0x01FF);
+}
+
+/*******************************************************************************
+* Function Name : USART_ReceiveData
+* Description : Returns the most recent received data by the USARTx peripheral.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* Output : None
+* Return : The received data.
+*******************************************************************************/
+u16 USART_ReceiveData(USART_TypeDef* USARTx)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+
+ /* Receive Data */
+ return (u16)(USARTx->DR & (u16)0x01FF);
+}
+
+/*******************************************************************************
+* Function Name : USART_SendBreak
+* Description : Transmits break characters.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_SendBreak(USART_TypeDef* USARTx)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+
+ /* Send break characters */
+ USARTx->CR1 |= CR1_SBK_Set;
+}
+
+/*******************************************************************************
+* Function Name : USART_SetGuardTime
+* Description : Sets the specified USART guard time.
+* Input : - USARTx: where x can be 1, 2 or 3 to select the USART
+* peripheral.
+* Note: The guard time bits are not available for UART4 and UART5.
+* - USART_GuardTime: specifies the guard time.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_SetGuardTime(USART_TypeDef* USARTx, u8 USART_GuardTime)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_123_PERIPH(USARTx));
+
+ /* Clear the USART Guard time */
+ USARTx->GTPR &= GTPR_LSB_Mask;
+ /* Set the USART guard time */
+ USARTx->GTPR |= (u16)((u16)USART_GuardTime << 0x08);
+}
+
+/*******************************************************************************
+* Function Name : USART_SetPrescaler
+* Description : Sets the system clock prescaler.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* Note: The function is used for IrDA mode with UART4 and UART5.
+* - USART_Prescaler: specifies the prescaler clock.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_SetPrescaler(USART_TypeDef* USARTx, u8 USART_Prescaler)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+
+ /* Clear the USART prescaler */
+ USARTx->GTPR &= GTPR_MSB_Mask;
+ /* Set the USART prescaler */
+ USARTx->GTPR |= USART_Prescaler;
+}
+
+/*******************************************************************************
+* Function Name : USART_SmartCardCmd
+* Description : Enables or disables the USART’s Smart Card mode.
+* Input : - USARTx: where x can be 1, 2 or 3 to select the USART
+* peripheral.
+* Note: The Smart Card mode is not available for UART4 and UART5.
+* - NewState: new state of the Smart Card mode.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_123_PERIPH(USARTx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the SC mode by setting the SCEN bit in the CR3 register */
+ USARTx->CR3 |= CR3_SCEN_Set;
+ }
+ else
+ {
+ /* Disable the SC mode by clearing the SCEN bit in the CR3 register */
+ USARTx->CR3 &= CR3_SCEN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_SmartCardNACKCmd
+* Description : Enables or disables NACK transmission.
+* Input : - USARTx: where x can be 1, 2 or 3 to select the USART
+* peripheral.
+* Note: The Smart Card mode is not available for UART4 and UART5.
+* - NewState: new state of the NACK transmission.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_123_PERIPH(USARTx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the NACK transmission by setting the NACK bit in the CR3 register */
+ USARTx->CR3 |= CR3_NACK_Set;
+ }
+ else
+ {
+ /* Disable the NACK transmission by clearing the NACK bit in the CR3 register */
+ USARTx->CR3 &= CR3_NACK_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_HalfDuplexCmd
+* Description : Enables or disables the USART’s Half Duplex communication.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - NewState: new state of the USART Communication.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */
+ USARTx->CR3 |= CR3_HDSEL_Set;
+ }
+ else
+ {
+ /* Disable the Half-Duplex mode by clearing the HDSEL bit in the CR3 register */
+ USARTx->CR3 &= CR3_HDSEL_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_IrDAConfig
+* Description : Configures the USART’s IrDA interface.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_IrDAMode: specifies the IrDA mode.
+* This parameter can be one of the following values:
+* - USART_IrDAMode_LowPower
+* - USART_IrDAMode_Normal
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_IrDAConfig(USART_TypeDef* USARTx, u16 USART_IrDAMode)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_IRDA_MODE(USART_IrDAMode));
+
+ USARTx->CR3 &= CR3_IRLP_Mask;
+ USARTx->CR3 |= USART_IrDAMode;
+}
+
+/*******************************************************************************
+* Function Name : USART_IrDACmd
+* Description : Enables or disables the USART’s IrDA interface.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - NewState: new state of the IrDA mode.
+* This parameter can be: ENABLE or DISABLE.
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+ if (NewState != DISABLE)
+ {
+ /* Enable the IrDA mode by setting the IREN bit in the CR3 register */
+ USARTx->CR3 |= CR3_IREN_Set;
+ }
+ else
+ {
+ /* Disable the IrDA mode by clearing the IREN bit in the CR3 register */
+ USARTx->CR3 &= CR3_IREN_Reset;
+ }
+}
+
+/*******************************************************************************
+* Function Name : USART_GetFlagStatus
+* Description : Checks whether the specified USART flag is set or not.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_FLAG: specifies the flag to check.
+* This parameter can be one of the following values:
+* - USART_FLAG_CTS: CTS Change flag (not available for
+* UART4 and UART5)
+* - USART_FLAG_LBD: LIN Break detection flag
+* - USART_FLAG_TXE: Transmit data register empty flag
+* - USART_FLAG_TC: Transmission Complete flag
+* - USART_FLAG_RXNE: Receive data register not empty flag
+* - USART_FLAG_IDLE: Idle Line detection flag
+* - USART_FLAG_ORE: OverRun Error flag
+* - USART_FLAG_NE: Noise Error flag
+* - USART_FLAG_FE: Framing Error flag
+* - USART_FLAG_PE: Parity Error flag
+* Output : None
+* Return : The new state of USART_FLAG (SET or RESET).
+*******************************************************************************/
+FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, u16 USART_FLAG)
+{
+ FlagStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_FLAG(USART_FLAG));
+ assert_param(IS_USART_PERIPH_FLAG(USARTx, USART_FLAG)); /* The CTS flag is not available for UART4 and UART5 */
+
+ if ((USARTx->SR & USART_FLAG) != (u16)RESET)
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : USART_ClearFlag
+* Description : Clears the USARTx's pending flags.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_FLAG: specifies the flag to clear.
+* This parameter can be any combination of the following values:
+* - USART_FLAG_CTS: CTS Change flag (not available for
+* UART4 and UART5).
+* - USART_FLAG_LBD: LIN Break detection flag.
+* - USART_FLAG_TC: Transmission Complete flag.
+* - USART_FLAG_RXNE: Receive data register not empty flag.
+*
+* Notes:
+* - PE (Parity error), FE (Framing error), NE (Noise error),
+* ORE (OverRun error) and IDLE (Idle line detected)
+* flags are cleared by software sequence: a read
+* operation to USART_SR register (USART_GetFlagStatus())
+* followed by a read operation to USART_DR register
+* (USART_ReceiveData()).
+* - RXNE flag can be also cleared by a read to the
+* USART_DR register (USART_ReceiveData()).
+* - TC flag can be also cleared by software sequence: a
+* read operation to USART_SR register
+* (USART_GetFlagStatus()) followed by a write operation
+* to USART_DR register (USART_SendData()).
+* - TXE flag is cleared only by a write to the USART_DR
+* register (USART_SendData()).
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_ClearFlag(USART_TypeDef* USARTx, u16 USART_FLAG)
+{
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_CLEAR_FLAG(USART_FLAG));
+ assert_param(IS_USART_PERIPH_FLAG(USARTx, USART_FLAG)); /* The CTS flag is not available for UART4 and UART5 */
+
+ USARTx->SR = (u16)~USART_FLAG;
+}
+
+/*******************************************************************************
+* Function Name : USART_GetITStatus
+* Description : Checks whether the specified USART interrupt has occurred or not.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_IT: specifies the USART interrupt source to check.
+* This parameter can be one of the following values:
+* - USART_IT_CTS: CTS change interrupt (not available for
+* UART4 and UART5)
+* - USART_IT_LBD: LIN Break detection interrupt
+* - USART_IT_TXE: Tansmit Data Register empty interrupt
+* - USART_IT_TC: Transmission complete interrupt
+* - USART_IT_RXNE: Receive Data register not empty
+* interrupt
+* - USART_IT_IDLE: Idle line detection interrupt
+* - USART_IT_ORE: OverRun Error interrupt
+* - USART_IT_NE: Noise Error interrupt
+* - USART_IT_FE: Framing Error interrupt
+* - USART_IT_PE: Parity Error interrupt
+* Output : None
+* Return : The new state of USART_IT (SET or RESET).
+*******************************************************************************/
+ITStatus USART_GetITStatus(USART_TypeDef* USARTx, u16 USART_IT)
+{
+ u32 bitpos = 0x00, itmask = 0x00, usartreg = 0x00;
+ ITStatus bitstatus = RESET;
+
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_GET_IT(USART_IT));
+ assert_param(IS_USART_PERIPH_IT(USARTx, USART_IT)); /* The CTS interrupt is not available for UART4 and UART5 */
+
+ /* Get the USART register index */
+ usartreg = (((u8)USART_IT) >> 0x05);
+
+ /* Get the interrupt position */
+ itmask = USART_IT & IT_Mask;
+
+ itmask = (u32)0x01 << itmask;
+
+ if (usartreg == 0x01) /* The IT is in CR1 register */
+ {
+ itmask &= USARTx->CR1;
+ }
+ else if (usartreg == 0x02) /* The IT is in CR2 register */
+ {
+ itmask &= USARTx->CR2;
+ }
+ else /* The IT is in CR3 register */
+ {
+ itmask &= USARTx->CR3;
+ }
+
+ bitpos = USART_IT >> 0x08;
+
+ bitpos = (u32)0x01 << bitpos;
+ bitpos &= USARTx->SR;
+
+ if ((itmask != (u16)RESET)&&(bitpos != (u16)RESET))
+ {
+ bitstatus = SET;
+ }
+ else
+ {
+ bitstatus = RESET;
+ }
+
+ return bitstatus;
+}
+
+/*******************************************************************************
+* Function Name : USART_ClearITPendingBit
+* Description : Clears the USARTx’s interrupt pending bits.
+* Input : - USARTx: Select the USART or the UART peripheral.
+* This parameter can be one of the following values:
+* - USART1, USART2, USART3, UART4 or UART5.
+* - USART_IT: specifies the interrupt pending bit to clear.
+* This parameter can be one of the following values:
+* - USART_IT_CTS: CTS change interrupt (not available for
+* UART4 and UART5)
+* - USART_IT_LBD: LIN Break detection interrupt
+* - USART_IT_TC: Transmission complete interrupt.
+* - USART_IT_RXNE: Receive Data register not empty interrupt.
+*
+* Notes:
+* - PE (Parity error), FE (Framing error), NE (Noise error),
+* ORE (OverRun error) and IDLE (Idle line detected)
+* pending bits are cleared by software sequence: a read
+* operation to USART_SR register (USART_GetITStatus())
+* followed by a read operation to USART_DR register
+* (USART_ReceiveData()).
+* - RXNE pending bit can be also cleared by a read to the
+* USART_DR register (USART_ReceiveData()).
+* - TC pending bit can be also cleared by software
+* sequence: a read operation to USART_SR register
+* (USART_GetITStatus()) followed by a write operation
+* to USART_DR register (USART_SendData()).
+* - TXE pending bit is cleared only by a write to the
+* USART_DR register (USART_SendData()).
+* Output : None
+* Return : None
+*******************************************************************************/
+void USART_ClearITPendingBit(USART_TypeDef* USARTx, u16 USART_IT)
+{
+ u16 bitpos = 0x00, itmask = 0x00;
+
+ /* Check the parameters */
+ assert_param(IS_USART_ALL_PERIPH(USARTx));
+ assert_param(IS_USART_CLEAR_IT(USART_IT));
+ assert_param(IS_USART_PERIPH_IT(USARTx, USART_IT)); /* The CTS interrupt is not available for UART4 and UART5 */
+
+ bitpos = USART_IT >> 0x08;
+
+ itmask = (u16)((u16)0x01 << bitpos);
+ USARTx->SR = (u16)~itmask;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/stm32lib/src/stm32f10x_usart.lst b/src/stm32lib/src/stm32f10x_usart.lst new file mode 100644 index 0000000..3ede4f1 --- /dev/null +++ b/src/stm32lib/src/stm32f10x_usart.lst @@ -0,0 +1,1990 @@ + 1 .syntax unified + 2 .cpu cortex-m3 + 3 .fpu softvfp + 4 .eabi_attribute 20, 1 + 5 .eabi_attribute 21, 1 + 6 .eabi_attribute 23, 3 + 7 .eabi_attribute 24, 1 + 8 .eabi_attribute 25, 1 + 9 .eabi_attribute 26, 1 + 10 .eabi_attribute 30, 4 + 11 .eabi_attribute 18, 4 + 12 .thumb + 13 .file "stm32f10x_usart.c" + 21 .Ltext0: + 22 .align 2 + 23 .global USART_StructInit + 24 .thumb + 25 .thumb_func + 27 USART_StructInit: + 28 .LFB25: + 29 .file 1 "stm32lib/src/stm32f10x_usart.c" + 1:stm32lib/src/stm32f10x_usart.c **** /******************** (C) COPYRIGHT 2008 STMicroelectronics ******************** + 2:stm32lib/src/stm32f10x_usart.c **** * File Name : stm32f10x_usart.c + 3:stm32lib/src/stm32f10x_usart.c **** * Author : MCD Application Team + 4:stm32lib/src/stm32f10x_usart.c **** * Version : V2.0.2 + 5:stm32lib/src/stm32f10x_usart.c **** * Date : 07/11/2008 + 6:stm32lib/src/stm32f10x_usart.c **** * Description : This file provides all the USART firmware functions. + 7:stm32lib/src/stm32f10x_usart.c **** ******************************************************************************** + 8:stm32lib/src/stm32f10x_usart.c **** * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + 9:stm32lib/src/stm32f10x_usart.c **** * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. + 10:stm32lib/src/stm32f10x_usart.c **** * AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, + 11:stm32lib/src/stm32f10x_usart.c **** * INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE + 12:stm32lib/src/stm32f10x_usart.c **** * CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING + 13:stm32lib/src/stm32f10x_usart.c **** * INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + 14:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 15:stm32lib/src/stm32f10x_usart.c **** + 16:stm32lib/src/stm32f10x_usart.c **** /* Includes ------------------------------------------------------------------*/ + 17:stm32lib/src/stm32f10x_usart.c **** #include "stm32f10x_usart.h" + 18:stm32lib/src/stm32f10x_usart.c **** #include "stm32f10x_rcc.h" + 19:stm32lib/src/stm32f10x_usart.c **** + 20:stm32lib/src/stm32f10x_usart.c **** /* Private typedef -----------------------------------------------------------*/ + 21:stm32lib/src/stm32f10x_usart.c **** /* Private define ------------------------------------------------------------*/ + 22:stm32lib/src/stm32f10x_usart.c **** /* USART UE Mask */ + 23:stm32lib/src/stm32f10x_usart.c **** #define CR1_UE_Set ((u16)0x2000) /* USART Enable Mask */ + 24:stm32lib/src/stm32f10x_usart.c **** #define CR1_UE_Reset ((u16)0xDFFF) /* USART Disable Mask */ + 25:stm32lib/src/stm32f10x_usart.c **** + 26:stm32lib/src/stm32f10x_usart.c **** /* USART WakeUp Method */ + 27:stm32lib/src/stm32f10x_usart.c **** #define CR1_WAKE_Mask ((u16)0xF7FF) /* USART WakeUp Method Mask */ + 28:stm32lib/src/stm32f10x_usart.c **** + 29:stm32lib/src/stm32f10x_usart.c **** /* USART RWU Mask */ + 30:stm32lib/src/stm32f10x_usart.c **** #define CR1_RWU_Set ((u16)0x0002) /* USART mute mode Enable Mask */ + 31:stm32lib/src/stm32f10x_usart.c **** #define CR1_RWU_Reset ((u16)0xFFFD) /* USART mute mode Enable Mask */ + 32:stm32lib/src/stm32f10x_usart.c **** + 33:stm32lib/src/stm32f10x_usart.c **** #define CR1_SBK_Set ((u16)0x0001) /* USART Break Character send Mask */ + 34:stm32lib/src/stm32f10x_usart.c **** + 35:stm32lib/src/stm32f10x_usart.c **** #define CR1_CLEAR_Mask ((u16)0xE9F3) /* USART CR1 Mask */ + 36:stm32lib/src/stm32f10x_usart.c **** + 37:stm32lib/src/stm32f10x_usart.c **** #define CR2_Address_Mask ((u16)0xFFF0) /* USART address Mask */ + 38:stm32lib/src/stm32f10x_usart.c **** + 39:stm32lib/src/stm32f10x_usart.c **** /* USART LIN Mask */ + 40:stm32lib/src/stm32f10x_usart.c **** #define CR2_LINEN_Set ((u16)0x4000) /* USART LIN Enable Mask */ + 41:stm32lib/src/stm32f10x_usart.c **** #define CR2_LINEN_Reset ((u16)0xBFFF) /* USART LIN Disable Mask */ + 42:stm32lib/src/stm32f10x_usart.c **** + 43:stm32lib/src/stm32f10x_usart.c **** /* USART LIN Break detection */ + 44:stm32lib/src/stm32f10x_usart.c **** #define CR2_LBDL_Mask ((u16)0xFFDF) /* USART LIN Break detection Mask */ + 45:stm32lib/src/stm32f10x_usart.c **** + 46:stm32lib/src/stm32f10x_usart.c **** #define CR2_STOP_CLEAR_Mask ((u16)0xCFFF) /* USART CR2 STOP Bits Mask */ + 47:stm32lib/src/stm32f10x_usart.c **** #define CR2_CLOCK_CLEAR_Mask ((u16)0xF0FF) /* USART CR2 Clock Mask */ + 48:stm32lib/src/stm32f10x_usart.c **** + 49:stm32lib/src/stm32f10x_usart.c **** /* USART SC Mask */ + 50:stm32lib/src/stm32f10x_usart.c **** #define CR3_SCEN_Set ((u16)0x0020) /* USART SC Enable Mask */ + 51:stm32lib/src/stm32f10x_usart.c **** #define CR3_SCEN_Reset ((u16)0xFFDF) /* USART SC Disable Mask */ + 52:stm32lib/src/stm32f10x_usart.c **** + 53:stm32lib/src/stm32f10x_usart.c **** /* USART SC NACK Mask */ + 54:stm32lib/src/stm32f10x_usart.c **** #define CR3_NACK_Set ((u16)0x0010) /* USART SC NACK Enable Mask */ + 55:stm32lib/src/stm32f10x_usart.c **** #define CR3_NACK_Reset ((u16)0xFFEF) /* USART SC NACK Disable Mask */ + 56:stm32lib/src/stm32f10x_usart.c **** + 57:stm32lib/src/stm32f10x_usart.c **** /* USART Half-Duplex Mask */ + 58:stm32lib/src/stm32f10x_usart.c **** #define CR3_HDSEL_Set ((u16)0x0008) /* USART Half-Duplex Enable Mask */ + 59:stm32lib/src/stm32f10x_usart.c **** #define CR3_HDSEL_Reset ((u16)0xFFF7) /* USART Half-Duplex Disable Mask */ + 60:stm32lib/src/stm32f10x_usart.c **** + 61:stm32lib/src/stm32f10x_usart.c **** /* USART IrDA Mask */ + 62:stm32lib/src/stm32f10x_usart.c **** #define CR3_IRLP_Mask ((u16)0xFFFB) /* USART IrDA LowPower mode Mask */ + 63:stm32lib/src/stm32f10x_usart.c **** + 64:stm32lib/src/stm32f10x_usart.c **** #define CR3_CLEAR_Mask ((u16)0xFCFF) /* USART CR3 Mask */ + 65:stm32lib/src/stm32f10x_usart.c **** + 66:stm32lib/src/stm32f10x_usart.c **** /* USART IrDA Mask */ + 67:stm32lib/src/stm32f10x_usart.c **** #define CR3_IREN_Set ((u16)0x0002) /* USART IrDA Enable Mask */ + 68:stm32lib/src/stm32f10x_usart.c **** #define CR3_IREN_Reset ((u16)0xFFFD) /* USART IrDA Disable Mask */ + 69:stm32lib/src/stm32f10x_usart.c **** + 70:stm32lib/src/stm32f10x_usart.c **** #define GTPR_LSB_Mask ((u16)0x00FF) /* Guard Time Register LSB Mask */ + 71:stm32lib/src/stm32f10x_usart.c **** #define GTPR_MSB_Mask ((u16)0xFF00) /* Guard Time Register MSB Mask */ + 72:stm32lib/src/stm32f10x_usart.c **** + 73:stm32lib/src/stm32f10x_usart.c **** #define IT_Mask ((u16)0x001F) /* USART Interrupt Mask */ + 74:stm32lib/src/stm32f10x_usart.c **** + 75:stm32lib/src/stm32f10x_usart.c **** /* Private macro -------------------------------------------------------------*/ + 76:stm32lib/src/stm32f10x_usart.c **** /* Private variables ---------------------------------------------------------*/ + 77:stm32lib/src/stm32f10x_usart.c **** /* Private function prototypes -----------------------------------------------*/ + 78:stm32lib/src/stm32f10x_usart.c **** /* Private functions ---------------------------------------------------------*/ + 79:stm32lib/src/stm32f10x_usart.c **** + 80:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 81:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_DeInit + 82:stm32lib/src/stm32f10x_usart.c **** * Description : Deinitializes the USARTx peripheral registers to their + 83:stm32lib/src/stm32f10x_usart.c **** * default reset values. + 84:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 85:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 86:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 87:stm32lib/src/stm32f10x_usart.c **** * Output : None + 88:stm32lib/src/stm32f10x_usart.c **** * Return : None + 89:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 90:stm32lib/src/stm32f10x_usart.c **** void USART_DeInit(USART_TypeDef* USARTx) + 91:stm32lib/src/stm32f10x_usart.c **** { + 92:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 93:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 94:stm32lib/src/stm32f10x_usart.c **** + 95:stm32lib/src/stm32f10x_usart.c **** switch (*(u32*)&USARTx) + 96:stm32lib/src/stm32f10x_usart.c **** { + 97:stm32lib/src/stm32f10x_usart.c **** case USART1_BASE: + 98:stm32lib/src/stm32f10x_usart.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, ENABLE); + 99:stm32lib/src/stm32f10x_usart.c **** RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, DISABLE); + 100:stm32lib/src/stm32f10x_usart.c **** break; + 101:stm32lib/src/stm32f10x_usart.c **** + 102:stm32lib/src/stm32f10x_usart.c **** case USART2_BASE: + 103:stm32lib/src/stm32f10x_usart.c **** RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, ENABLE); + 104:stm32lib/src/stm32f10x_usart.c **** RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, DISABLE); + 105:stm32lib/src/stm32f10x_usart.c **** break; + 106:stm32lib/src/stm32f10x_usart.c **** + 107:stm32lib/src/stm32f10x_usart.c **** case USART3_BASE: + 108:stm32lib/src/stm32f10x_usart.c **** RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, ENABLE); + 109:stm32lib/src/stm32f10x_usart.c **** RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, DISABLE); + 110:stm32lib/src/stm32f10x_usart.c **** break; + 111:stm32lib/src/stm32f10x_usart.c **** + 112:stm32lib/src/stm32f10x_usart.c **** case UART4_BASE: + 113:stm32lib/src/stm32f10x_usart.c **** RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, ENABLE); + 114:stm32lib/src/stm32f10x_usart.c **** RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, DISABLE); + 115:stm32lib/src/stm32f10x_usart.c **** break; + 116:stm32lib/src/stm32f10x_usart.c **** + 117:stm32lib/src/stm32f10x_usart.c **** case UART5_BASE: + 118:stm32lib/src/stm32f10x_usart.c **** RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, ENABLE); + 119:stm32lib/src/stm32f10x_usart.c **** RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, DISABLE); + 120:stm32lib/src/stm32f10x_usart.c **** break; + 121:stm32lib/src/stm32f10x_usart.c **** + 122:stm32lib/src/stm32f10x_usart.c **** default: + 123:stm32lib/src/stm32f10x_usart.c **** break; + 124:stm32lib/src/stm32f10x_usart.c **** } + 125:stm32lib/src/stm32f10x_usart.c **** } + 126:stm32lib/src/stm32f10x_usart.c **** + 127:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 128:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_Init + 129:stm32lib/src/stm32f10x_usart.c **** * Description : Initializes the USARTx peripheral according to the specified + 130:stm32lib/src/stm32f10x_usart.c **** * parameters in the USART_InitStruct . + 131:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 132:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 133:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 134:stm32lib/src/stm32f10x_usart.c **** * - USART_InitStruct: pointer to a USART_InitTypeDef structure + 135:stm32lib/src/stm32f10x_usart.c **** * that contains the configuration information for the + 136:stm32lib/src/stm32f10x_usart.c **** * specified USART peripheral. + 137:stm32lib/src/stm32f10x_usart.c **** * Output : None + 138:stm32lib/src/stm32f10x_usart.c **** * Return : None + 139:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 140:stm32lib/src/stm32f10x_usart.c **** void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct) + 141:stm32lib/src/stm32f10x_usart.c **** { + 142:stm32lib/src/stm32f10x_usart.c **** u32 tmpreg = 0x00, apbclock = 0x00; + 143:stm32lib/src/stm32f10x_usart.c **** u32 integerdivider = 0x00; + 144:stm32lib/src/stm32f10x_usart.c **** u32 fractionaldivider = 0x00; + 145:stm32lib/src/stm32f10x_usart.c **** u32 usartxbase = 0; + 146:stm32lib/src/stm32f10x_usart.c **** RCC_ClocksTypeDef RCC_ClocksStatus; + 147:stm32lib/src/stm32f10x_usart.c **** + 148:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 149:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 150:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_BAUDRATE(USART_InitStruct->USART_BaudRate)); + 151:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_WORD_LENGTH(USART_InitStruct->USART_WordLength)); + 152:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_STOPBITS(USART_InitStruct->USART_StopBits)); + 153:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_PARITY(USART_InitStruct->USART_Parity)); + 154:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_MODE(USART_InitStruct->USART_Mode)); + 155:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_HARDWARE_FLOW_CONTROL(USART_InitStruct->USART_HardwareFlowControl)); + 156:stm32lib/src/stm32f10x_usart.c **** /* The hardware flow control is available only for USART1, USART2 and USART3 */ + 157:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_PERIPH_HFC(USARTx, USART_InitStruct->USART_HardwareFlowControl)); + 158:stm32lib/src/stm32f10x_usart.c **** + 159:stm32lib/src/stm32f10x_usart.c **** usartxbase = (*(u32*)&USARTx); + 160:stm32lib/src/stm32f10x_usart.c **** + 161:stm32lib/src/stm32f10x_usart.c **** /*---------------------------- USART CR2 Configuration -----------------------*/ + 162:stm32lib/src/stm32f10x_usart.c **** tmpreg = USARTx->CR2; + 163:stm32lib/src/stm32f10x_usart.c **** /* Clear STOP[13:12] bits */ + 164:stm32lib/src/stm32f10x_usart.c **** tmpreg &= CR2_STOP_CLEAR_Mask; + 165:stm32lib/src/stm32f10x_usart.c **** + 166:stm32lib/src/stm32f10x_usart.c **** /* Configure the USART Stop Bits, Clock, CPOL, CPHA and LastBit ------------*/ + 167:stm32lib/src/stm32f10x_usart.c **** /* Set STOP[13:12] bits according to USART_StopBits value */ + 168:stm32lib/src/stm32f10x_usart.c **** tmpreg |= (u32)USART_InitStruct->USART_StopBits; + 169:stm32lib/src/stm32f10x_usart.c **** + 170:stm32lib/src/stm32f10x_usart.c **** /* Write to USART CR2 */ + 171:stm32lib/src/stm32f10x_usart.c **** USARTx->CR2 = (u16)tmpreg; + 172:stm32lib/src/stm32f10x_usart.c **** + 173:stm32lib/src/stm32f10x_usart.c **** /*---------------------------- USART CR1 Configuration -----------------------*/ + 174:stm32lib/src/stm32f10x_usart.c **** tmpreg = USARTx->CR1; + 175:stm32lib/src/stm32f10x_usart.c **** /* Clear M, PCE, PS, TE and RE bits */ + 176:stm32lib/src/stm32f10x_usart.c **** tmpreg &= CR1_CLEAR_Mask; + 177:stm32lib/src/stm32f10x_usart.c **** + 178:stm32lib/src/stm32f10x_usart.c **** /* Configure the USART Word Length, Parity and mode ----------------------- */ + 179:stm32lib/src/stm32f10x_usart.c **** /* Set the M bits according to USART_WordLength value */ + 180:stm32lib/src/stm32f10x_usart.c **** /* Set PCE and PS bits according to USART_Parity value */ + 181:stm32lib/src/stm32f10x_usart.c **** /* Set TE and RE bits according to USART_Mode value */ + 182:stm32lib/src/stm32f10x_usart.c **** tmpreg |= (u32)USART_InitStruct->USART_WordLength | USART_InitStruct->USART_Parity | + 183:stm32lib/src/stm32f10x_usart.c **** USART_InitStruct->USART_Mode; + 184:stm32lib/src/stm32f10x_usart.c **** + 185:stm32lib/src/stm32f10x_usart.c **** /* Write to USART CR1 */ + 186:stm32lib/src/stm32f10x_usart.c **** USARTx->CR1 = (u16)tmpreg; + 187:stm32lib/src/stm32f10x_usart.c **** + 188:stm32lib/src/stm32f10x_usart.c **** /*---------------------------- USART CR3 Configuration -----------------------*/ + 189:stm32lib/src/stm32f10x_usart.c **** tmpreg = USARTx->CR3; + 190:stm32lib/src/stm32f10x_usart.c **** /* Clear CTSE and RTSE bits */ + 191:stm32lib/src/stm32f10x_usart.c **** tmpreg &= CR3_CLEAR_Mask; + 192:stm32lib/src/stm32f10x_usart.c **** + 193:stm32lib/src/stm32f10x_usart.c **** /* Configure the USART HFC -------------------------------------------------*/ + 194:stm32lib/src/stm32f10x_usart.c **** /* Set CTSE and RTSE bits according to USART_HardwareFlowControl value */ + 195:stm32lib/src/stm32f10x_usart.c **** tmpreg |= USART_InitStruct->USART_HardwareFlowControl; + 196:stm32lib/src/stm32f10x_usart.c **** + 197:stm32lib/src/stm32f10x_usart.c **** /* Write to USART CR3 */ + 198:stm32lib/src/stm32f10x_usart.c **** USARTx->CR3 = (u16)tmpreg; + 199:stm32lib/src/stm32f10x_usart.c **** + 200:stm32lib/src/stm32f10x_usart.c **** /*---------------------------- USART BRR Configuration -----------------------*/ + 201:stm32lib/src/stm32f10x_usart.c **** /* Configure the USART Baud Rate -------------------------------------------*/ + 202:stm32lib/src/stm32f10x_usart.c **** RCC_GetClocksFreq(&RCC_ClocksStatus); + 203:stm32lib/src/stm32f10x_usart.c **** if (usartxbase == USART1_BASE) + 204:stm32lib/src/stm32f10x_usart.c **** { + 205:stm32lib/src/stm32f10x_usart.c **** apbclock = RCC_ClocksStatus.PCLK2_Frequency; + 206:stm32lib/src/stm32f10x_usart.c **** } + 207:stm32lib/src/stm32f10x_usart.c **** else + 208:stm32lib/src/stm32f10x_usart.c **** { + 209:stm32lib/src/stm32f10x_usart.c **** apbclock = RCC_ClocksStatus.PCLK1_Frequency; + 210:stm32lib/src/stm32f10x_usart.c **** } + 211:stm32lib/src/stm32f10x_usart.c **** + 212:stm32lib/src/stm32f10x_usart.c **** /* Determine the integer part */ + 213:stm32lib/src/stm32f10x_usart.c **** integerdivider = ((0x19 * apbclock) / (0x04 * (USART_InitStruct->USART_BaudRate))); + 214:stm32lib/src/stm32f10x_usart.c **** tmpreg = (integerdivider / 0x64) << 0x04; + 215:stm32lib/src/stm32f10x_usart.c **** + 216:stm32lib/src/stm32f10x_usart.c **** /* Determine the fractional part */ + 217:stm32lib/src/stm32f10x_usart.c **** fractionaldivider = integerdivider - (0x64 * (tmpreg >> 0x04)); + 218:stm32lib/src/stm32f10x_usart.c **** tmpreg |= ((((fractionaldivider * 0x10) + 0x32) / 0x64)) & ((u8)0x0F); + 219:stm32lib/src/stm32f10x_usart.c **** + 220:stm32lib/src/stm32f10x_usart.c **** /* Write to USART BRR */ + 221:stm32lib/src/stm32f10x_usart.c **** USARTx->BRR = (u16)tmpreg; + 222:stm32lib/src/stm32f10x_usart.c **** } + 223:stm32lib/src/stm32f10x_usart.c **** + 224:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 225:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_StructInit + 226:stm32lib/src/stm32f10x_usart.c **** * Description : Fills each USART_InitStruct member with its default value. + 227:stm32lib/src/stm32f10x_usart.c **** * Input : - USART_InitStruct: pointer to a USART_InitTypeDef structure + 228:stm32lib/src/stm32f10x_usart.c **** * which will be initialized. + 229:stm32lib/src/stm32f10x_usart.c **** * Output : None + 230:stm32lib/src/stm32f10x_usart.c **** * Return : None + 231:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 232:stm32lib/src/stm32f10x_usart.c **** void USART_StructInit(USART_InitTypeDef* USART_InitStruct) + 233:stm32lib/src/stm32f10x_usart.c **** { + 30 .loc 1 233 0 + 31 @ args = 0, pretend = 0, frame = 0 + 32 @ frame_needed = 0, uses_anonymous_args = 0 + 33 @ link register save eliminated. + 34 .LVL0: + 234:stm32lib/src/stm32f10x_usart.c **** /* USART_InitStruct members default value */ + 235:stm32lib/src/stm32f10x_usart.c **** USART_InitStruct->USART_BaudRate = 9600; + 35 .loc 1 235 0 + 36 0000 4FF41653 mov r3, #9600 + 37 0004 0360 str r3, [r0, #0] + 236:stm32lib/src/stm32f10x_usart.c **** USART_InitStruct->USART_WordLength = USART_WordLength_8b; + 237:stm32lib/src/stm32f10x_usart.c **** USART_InitStruct->USART_StopBits = USART_StopBits_1; + 238:stm32lib/src/stm32f10x_usart.c **** USART_InitStruct->USART_Parity = USART_Parity_No ; + 239:stm32lib/src/stm32f10x_usart.c **** USART_InitStruct->USART_Mode = USART_Mode_Rx | USART_Mode_Tx; + 38 .loc 1 239 0 + 39 0006 4FF00C02 mov r2, #12 @ movhi + 40 .loc 1 236 0 + 41 000a A3F51653 sub r3, r3, #9600 + 42 000e 8380 strh r3, [r0, #4] @ movhi + 43 .loc 1 237 0 + 44 0010 C380 strh r3, [r0, #6] @ movhi + 45 .loc 1 238 0 + 46 0012 0381 strh r3, [r0, #8] @ movhi + 47 .loc 1 239 0 + 48 0014 4281 strh r2, [r0, #10] @ movhi + 240:stm32lib/src/stm32f10x_usart.c **** USART_InitStruct->USART_HardwareFlowControl = USART_HardwareFlowControl_None; + 49 .loc 1 240 0 + 50 0016 8381 strh r3, [r0, #12] @ movhi + 241:stm32lib/src/stm32f10x_usart.c **** } + 51 .loc 1 241 0 + 52 0018 7047 bx lr + 53 .LFE25: + 55 001a 00BF .align 2 + 56 .global USART_ClockInit + 57 .thumb + 58 .thumb_func + 60 USART_ClockInit: + 61 .LFB26: + 242:stm32lib/src/stm32f10x_usart.c **** + 243:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 244:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_ClockInit + 245:stm32lib/src/stm32f10x_usart.c **** * Description : Initializes the USARTx peripheral Clock according to the + 246:stm32lib/src/stm32f10x_usart.c **** * specified parameters in the USART_ClockInitStruct . + 247:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: where x can be 1, 2, 3 to select the USART peripheral. + 248:stm32lib/src/stm32f10x_usart.c **** * Note: The Smart Card mode is not available for UART4 and UART5. + 249:stm32lib/src/stm32f10x_usart.c **** * - USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef + 250:stm32lib/src/stm32f10x_usart.c **** * structure that contains the configuration information for + 251:stm32lib/src/stm32f10x_usart.c **** * the specified USART peripheral. + 252:stm32lib/src/stm32f10x_usart.c **** * Output : None + 253:stm32lib/src/stm32f10x_usart.c **** * Return : None + 254:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 255:stm32lib/src/stm32f10x_usart.c **** void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct) + 256:stm32lib/src/stm32f10x_usart.c **** { + 62 .loc 1 256 0 + 63 @ args = 0, pretend = 0, frame = 0 + 64 @ frame_needed = 0, uses_anonymous_args = 0 + 65 .LVL1: + 257:stm32lib/src/stm32f10x_usart.c **** u32 tmpreg = 0x00; + 258:stm32lib/src/stm32f10x_usart.c **** + 259:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 260:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_123_PERIPH(USARTx)); + 261:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_CLOCK(USART_ClockInitStruct->USART_Clock)); + 262:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_CPOL(USART_ClockInitStruct->USART_CPOL)); + 263:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_CPHA(USART_ClockInitStruct->USART_CPHA)); + 264:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_LASTBIT(USART_ClockInitStruct->USART_LastBit)); + 265:stm32lib/src/stm32f10x_usart.c **** + 266:stm32lib/src/stm32f10x_usart.c **** /*---------------------------- USART CR2 Configuration -----------------------*/ + 267:stm32lib/src/stm32f10x_usart.c **** tmpreg = USARTx->CR2; + 268:stm32lib/src/stm32f10x_usart.c **** /* Clear CLKEN, CPOL, CPHA and LBCL bits */ + 269:stm32lib/src/stm32f10x_usart.c **** tmpreg &= CR2_CLOCK_CLEAR_Mask; + 270:stm32lib/src/stm32f10x_usart.c **** + 271:stm32lib/src/stm32f10x_usart.c **** /* Configure the USART Clock, CPOL, CPHA and LastBit ------------*/ + 272:stm32lib/src/stm32f10x_usart.c **** /* Set CLKEN bit according to USART_Clock value */ + 273:stm32lib/src/stm32f10x_usart.c **** /* Set CPOL bit according to USART_CPOL value */ + 274:stm32lib/src/stm32f10x_usart.c **** /* Set CPHA bit according to USART_CPHA value */ + 275:stm32lib/src/stm32f10x_usart.c **** /* Set LBCL bit according to USART_LastBit value */ + 276:stm32lib/src/stm32f10x_usart.c **** tmpreg |= (u32)USART_ClockInitStruct->USART_Clock | USART_ClockInitStruct->USART_CPOL | + 277:stm32lib/src/stm32f10x_usart.c **** USART_ClockInitStruct->USART_CPHA | USART_ClockInitStruct->USART_LastBit; + 278:stm32lib/src/stm32f10x_usart.c **** + 279:stm32lib/src/stm32f10x_usart.c **** /* Write to USART CR2 */ + 280:stm32lib/src/stm32f10x_usart.c **** USARTx->CR2 = (u16)tmpreg; + 66 .loc 1 280 0 + 67 001c 4B88 ldrh r3, [r1, #2] + 68 .loc 1 256 0 + 69 001e 10B5 push {r4, lr} + 70 .LCFI0: + 71 .loc 1 280 0 + 72 0020 0C88 ldrh r4, [r1, #0] + 73 .loc 1 267 0 + 74 0022 028A ldrh r2, [r0, #16] + 75 .loc 1 280 0 + 76 0024 2343 orrs r3, r3, r4 + 77 0026 8C88 ldrh r4, [r1, #4] + 78 0028 C988 ldrh r1, [r1, #6] + 79 .LVL2: + 80 .loc 1 269 0 + 81 002a 22F47062 bic r2, r2, #3840 + 82 .LVL3: + 83 .loc 1 280 0 + 84 002e 2343 orrs r3, r3, r4 + 85 .loc 1 269 0 + 86 0030 1204 lsls r2, r2, #16 + 87 .loc 1 280 0 + 88 0032 0B43 orrs r3, r3, r1 + 89 .loc 1 269 0 + 90 0034 120C lsrs r2, r2, #16 + 91 .loc 1 280 0 + 92 0036 9BB2 uxth r3, r3 + 93 0038 1343 orrs r3, r3, r2 + 94 003a 0382 strh r3, [r0, #16] @ movhi + 281:stm32lib/src/stm32f10x_usart.c **** } + 95 .loc 1 281 0 + 96 003c 10BD pop {r4, pc} + 97 .LFE26: + 99 003e 00BF .align 2 + 100 .global USART_ClockStructInit + 101 .thumb + 102 .thumb_func + 104 USART_ClockStructInit: + 105 .LFB27: + 282:stm32lib/src/stm32f10x_usart.c **** + 283:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 284:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_ClockStructInit + 285:stm32lib/src/stm32f10x_usart.c **** * Description : Fills each USART_ClockInitStruct member with its default value. + 286:stm32lib/src/stm32f10x_usart.c **** * Input : - USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef + 287:stm32lib/src/stm32f10x_usart.c **** * structure which will be initialized. + 288:stm32lib/src/stm32f10x_usart.c **** * Output : None + 289:stm32lib/src/stm32f10x_usart.c **** * Return : None + 290:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 291:stm32lib/src/stm32f10x_usart.c **** void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct) + 292:stm32lib/src/stm32f10x_usart.c **** { + 106 .loc 1 292 0 + 107 @ args = 0, pretend = 0, frame = 0 + 108 @ frame_needed = 0, uses_anonymous_args = 0 + 109 @ link register save eliminated. + 110 .LVL4: + 293:stm32lib/src/stm32f10x_usart.c **** /* USART_ClockInitStruct members default value */ + 294:stm32lib/src/stm32f10x_usart.c **** USART_ClockInitStruct->USART_Clock = USART_Clock_Disable; + 111 .loc 1 294 0 + 112 0040 0023 movs r3, #0 + 113 0042 0380 strh r3, [r0, #0] @ movhi + 295:stm32lib/src/stm32f10x_usart.c **** USART_ClockInitStruct->USART_CPOL = USART_CPOL_Low; + 114 .loc 1 295 0 + 115 0044 4380 strh r3, [r0, #2] @ movhi + 296:stm32lib/src/stm32f10x_usart.c **** USART_ClockInitStruct->USART_CPHA = USART_CPHA_1Edge; + 116 .loc 1 296 0 + 117 0046 8380 strh r3, [r0, #4] @ movhi + 297:stm32lib/src/stm32f10x_usart.c **** USART_ClockInitStruct->USART_LastBit = USART_LastBit_Disable; + 118 .loc 1 297 0 + 119 0048 C380 strh r3, [r0, #6] @ movhi + 298:stm32lib/src/stm32f10x_usart.c **** } + 120 .loc 1 298 0 + 121 004a 7047 bx lr + 122 .LFE27: + 124 .align 2 + 125 .global USART_Cmd + 126 .thumb + 127 .thumb_func + 129 USART_Cmd: + 130 .LFB28: + 299:stm32lib/src/stm32f10x_usart.c **** + 300:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 301:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_Cmd + 302:stm32lib/src/stm32f10x_usart.c **** * Description : Enables or disables the specified USART peripheral. + 303:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 304:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 305:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 306:stm32lib/src/stm32f10x_usart.c **** * : - NewState: new state of the USARTx peripheral. + 307:stm32lib/src/stm32f10x_usart.c **** * This parameter can be: ENABLE or DISABLE. + 308:stm32lib/src/stm32f10x_usart.c **** * Output : None + 309:stm32lib/src/stm32f10x_usart.c **** * Return : None + 310:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 311:stm32lib/src/stm32f10x_usart.c **** void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState) + 312:stm32lib/src/stm32f10x_usart.c **** { + 131 .loc 1 312 0 + 132 @ args = 0, pretend = 0, frame = 0 + 133 @ frame_needed = 0, uses_anonymous_args = 0 + 134 @ link register save eliminated. + 135 .LVL5: + 313:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 314:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 315:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 316:stm32lib/src/stm32f10x_usart.c **** + 317:stm32lib/src/stm32f10x_usart.c **** if (NewState != DISABLE) + 136 .loc 1 317 0 + 137 004c 21B1 cbz r1, .L8 + 318:stm32lib/src/stm32f10x_usart.c **** { + 319:stm32lib/src/stm32f10x_usart.c **** /* Enable the selected USART by setting the UE bit in the CR1 register */ + 320:stm32lib/src/stm32f10x_usart.c **** USARTx->CR1 |= CR1_UE_Set; + 138 .loc 1 320 0 + 139 004e 8389 ldrh r3, [r0, #12] + 140 0050 9BB2 uxth r3, r3 + 141 0052 43F40053 orr r3, r3, #8192 + 142 0056 04E0 b .L11 + 143 .L8: + 321:stm32lib/src/stm32f10x_usart.c **** } + 322:stm32lib/src/stm32f10x_usart.c **** else + 323:stm32lib/src/stm32f10x_usart.c **** { + 324:stm32lib/src/stm32f10x_usart.c **** /* Disable the selected USART by clearing the UE bit in the CR1 register */ + 325:stm32lib/src/stm32f10x_usart.c **** USARTx->CR1 &= CR1_UE_Reset; + 144 .loc 1 325 0 + 145 0058 8389 ldrh r3, [r0, #12] + 146 005a 23F40053 bic r3, r3, #8192 + 147 005e 1B04 lsls r3, r3, #16 + 148 0060 1B0C lsrs r3, r3, #16 + 149 .L11: + 150 0062 8381 strh r3, [r0, #12] @ movhi + 326:stm32lib/src/stm32f10x_usart.c **** } + 327:stm32lib/src/stm32f10x_usart.c **** } + 151 .loc 1 327 0 + 152 0064 7047 bx lr + 153 .LFE28: + 155 0066 00BF .align 2 + 156 .global USART_ITConfig + 157 .thumb + 158 .thumb_func + 160 USART_ITConfig: + 161 .LFB29: + 328:stm32lib/src/stm32f10x_usart.c **** + 329:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 330:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_ITConfig + 331:stm32lib/src/stm32f10x_usart.c **** * Description : Enables or disables the specified USART interrupts. + 332:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 333:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 334:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 335:stm32lib/src/stm32f10x_usart.c **** * - USART_IT: specifies the USART interrupt sources to be + 336:stm32lib/src/stm32f10x_usart.c **** * enabled or disabled. + 337:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 338:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_CTS: CTS change interrupt (not available for + 339:stm32lib/src/stm32f10x_usart.c **** * UART4 and UART5) + 340:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_LBD: LIN Break detection interrupt + 341:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_TXE: Tansmit Data Register empty interrupt + 342:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_TC: Transmission complete interrupt + 343:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_RXNE: Receive Data register not empty + 344:stm32lib/src/stm32f10x_usart.c **** * interrupt + 345:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_IDLE: Idle line detection interrupt + 346:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_PE: Parity Error interrupt + 347:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_ERR: Error interrupt(Frame error, noise + 348:stm32lib/src/stm32f10x_usart.c **** * error, overrun error) + 349:stm32lib/src/stm32f10x_usart.c **** * - NewState: new state of the specified USARTx interrupts. + 350:stm32lib/src/stm32f10x_usart.c **** * This parameter can be: ENABLE or DISABLE. + 351:stm32lib/src/stm32f10x_usart.c **** * Output : None + 352:stm32lib/src/stm32f10x_usart.c **** * Return : None + 353:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 354:stm32lib/src/stm32f10x_usart.c **** void USART_ITConfig(USART_TypeDef* USARTx, u16 USART_IT, FunctionalState NewState) + 355:stm32lib/src/stm32f10x_usart.c **** { + 162 .loc 1 355 0 + 163 @ args = 0, pretend = 0, frame = 8 + 164 @ frame_needed = 0, uses_anonymous_args = 0 + 165 @ link register save eliminated. + 166 .LVL6: + 356:stm32lib/src/stm32f10x_usart.c **** u32 usartreg = 0x00, itpos = 0x00, itmask = 0x00; + 357:stm32lib/src/stm32f10x_usart.c **** u32 usartxbase = 0x00; + 358:stm32lib/src/stm32f10x_usart.c **** + 359:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 360:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 361:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_CONFIG_IT(USART_IT)); + 362:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_PERIPH_IT(USARTx, USART_IT)); /* The CTS interrupt is not available for UAR + 363:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 364:stm32lib/src/stm32f10x_usart.c **** + 365:stm32lib/src/stm32f10x_usart.c **** usartxbase = (*(u32*)&(USARTx)); + 366:stm32lib/src/stm32f10x_usart.c **** + 367:stm32lib/src/stm32f10x_usart.c **** /* Get the USART register index */ + 368:stm32lib/src/stm32f10x_usart.c **** usartreg = (((u8)USART_IT) >> 0x05); + 167 .loc 1 368 0 + 168 0068 C1F3421C ubfx ip, r1, #5, #3 + 169 .LVL7: + 369:stm32lib/src/stm32f10x_usart.c **** + 370:stm32lib/src/stm32f10x_usart.c **** /* Get the interrupt position */ + 371:stm32lib/src/stm32f10x_usart.c **** itpos = USART_IT & IT_Mask; + 372:stm32lib/src/stm32f10x_usart.c **** + 373:stm32lib/src/stm32f10x_usart.c **** itmask = (((u32)0x01) << itpos); + 170 .loc 1 373 0 + 171 006c 0123 movs r3, #1 + 172 006e 01F01F01 and r1, r1, #31 + 173 .LVL8: + 174 .loc 1 355 0 + 175 0072 82B0 sub sp, sp, #8 + 176 .LCFI1: + 177 .loc 1 373 0 + 178 0074 13FA01F1 lsls r1, r3, r1 + 179 .LVL9: + 374:stm32lib/src/stm32f10x_usart.c **** + 375:stm32lib/src/stm32f10x_usart.c **** if (usartreg == 0x01) /* The IT is in CR1 register */ + 180 .loc 1 375 0 + 181 0078 9C45 cmp ip, r3 + 182 .loc 1 355 0 + 183 007a 0190 str r0, [sp, #4] + 184 .loc 1 375 0 + 185 007c 01D1 bne .L13 + 186 .LVL10: + 376:stm32lib/src/stm32f10x_usart.c **** { + 377:stm32lib/src/stm32f10x_usart.c **** usartxbase += 0x0C; + 187 .loc 1 377 0 + 188 007e 0C30 adds r0, r0, #12 + 189 .LVL11: + 190 0080 05E0 b .L14 + 191 .LVL12: + 192 .L13: + 378:stm32lib/src/stm32f10x_usart.c **** } + 379:stm32lib/src/stm32f10x_usart.c **** else if (usartreg == 0x02) /* The IT is in CR2 register */ + 193 .loc 1 379 0 + 194 0082 BCF1020F cmp ip, #2 + 195 0086 01D1 bne .L15 + 380:stm32lib/src/stm32f10x_usart.c **** { + 381:stm32lib/src/stm32f10x_usart.c **** usartxbase += 0x10; + 196 .loc 1 381 0 + 197 0088 1030 adds r0, r0, #16 + 198 .LVL13: + 199 008a 00E0 b .L14 + 200 .LVL14: + 201 .L15: + 382:stm32lib/src/stm32f10x_usart.c **** } + 383:stm32lib/src/stm32f10x_usart.c **** else /* The IT is in CR3 register */ + 384:stm32lib/src/stm32f10x_usart.c **** { + 385:stm32lib/src/stm32f10x_usart.c **** usartxbase += 0x14; + 202 .loc 1 385 0 + 203 008c 1430 adds r0, r0, #20 + 204 .LVL15: + 205 .L14: + 386:stm32lib/src/stm32f10x_usart.c **** } + 387:stm32lib/src/stm32f10x_usart.c **** if (NewState != DISABLE) + 206 .loc 1 387 0 + 207 008e 12B1 cbz r2, .L16 + 388:stm32lib/src/stm32f10x_usart.c **** { + 389:stm32lib/src/stm32f10x_usart.c **** *(vu32*)usartxbase |= itmask; + 208 .loc 1 389 0 + 209 0090 0368 ldr r3, [r0, #0] + 210 0092 0B43 orrs r3, r3, r1 + 211 0094 02E0 b .L19 + 212 .L16: + 390:stm32lib/src/stm32f10x_usart.c **** } + 391:stm32lib/src/stm32f10x_usart.c **** else + 392:stm32lib/src/stm32f10x_usart.c **** { + 393:stm32lib/src/stm32f10x_usart.c **** *(vu32*)usartxbase &= ~itmask; + 213 .loc 1 393 0 + 214 0096 0368 ldr r3, [r0, #0] + 215 0098 23EA0103 bic r3, r3, r1 + 216 .L19: + 217 009c 0360 str r3, [r0, #0] + 394:stm32lib/src/stm32f10x_usart.c **** } + 395:stm32lib/src/stm32f10x_usart.c **** } + 218 .loc 1 395 0 + 219 009e 02B0 add sp, sp, #8 + 220 00a0 7047 bx lr + 221 .LFE29: + 223 00a2 00BF .align 2 + 224 .global USART_DMACmd + 225 .thumb + 226 .thumb_func + 228 USART_DMACmd: + 229 .LFB30: + 396:stm32lib/src/stm32f10x_usart.c **** + 397:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 398:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_DMACmd + 399:stm32lib/src/stm32f10x_usart.c **** * Description : Enables or disables the USART’s DMA interface. + 400:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 401:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 402:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3 or UART4. + 403:stm32lib/src/stm32f10x_usart.c **** * Note: The DMA mode is not available for UART5. + 404:stm32lib/src/stm32f10x_usart.c **** * - USART_DMAReq: specifies the DMA request. + 405:stm32lib/src/stm32f10x_usart.c **** * This parameter can be any combination of the following values: + 406:stm32lib/src/stm32f10x_usart.c **** * - USART_DMAReq_Tx: USART DMA transmit request + 407:stm32lib/src/stm32f10x_usart.c **** * - USART_DMAReq_Rx: USART DMA receive request + 408:stm32lib/src/stm32f10x_usart.c **** * - NewState: new state of the DMA Request sources. + 409:stm32lib/src/stm32f10x_usart.c **** * This parameter can be: ENABLE or DISABLE. + 410:stm32lib/src/stm32f10x_usart.c **** * Output : None + 411:stm32lib/src/stm32f10x_usart.c **** * Return : None + 412:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 413:stm32lib/src/stm32f10x_usart.c **** void USART_DMACmd(USART_TypeDef* USARTx, u16 USART_DMAReq, FunctionalState NewState) + 414:stm32lib/src/stm32f10x_usart.c **** { + 230 .loc 1 414 0 + 231 @ args = 0, pretend = 0, frame = 0 + 232 @ frame_needed = 0, uses_anonymous_args = 0 + 233 @ link register save eliminated. + 234 .LVL16: + 415:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 416:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_1234_PERIPH(USARTx)); + 417:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_DMAREQ(USART_DMAReq)); + 418:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 419:stm32lib/src/stm32f10x_usart.c **** + 420:stm32lib/src/stm32f10x_usart.c **** if (NewState != DISABLE) + 235 .loc 1 420 0 + 236 00a4 22B1 cbz r2, .L21 + 421:stm32lib/src/stm32f10x_usart.c **** { + 422:stm32lib/src/stm32f10x_usart.c **** /* Enable the DMA transfer for selected requests by setting the DMAT and/or + 423:stm32lib/src/stm32f10x_usart.c **** DMAR bits in the USART CR3 register */ + 424:stm32lib/src/stm32f10x_usart.c **** USARTx->CR3 |= USART_DMAReq; + 237 .loc 1 424 0 + 238 00a6 838A ldrh r3, [r0, #20] + 239 00a8 9BB2 uxth r3, r3 + 240 00aa 41EA0303 orr r3, r1, r3 + 241 00ae 03E0 b .L24 + 242 .L21: + 425:stm32lib/src/stm32f10x_usart.c **** } + 426:stm32lib/src/stm32f10x_usart.c **** else + 427:stm32lib/src/stm32f10x_usart.c **** { + 428:stm32lib/src/stm32f10x_usart.c **** /* Disable the DMA transfer for selected requests by clearing the DMAT and/or + 429:stm32lib/src/stm32f10x_usart.c **** DMAR bits in the USART CR3 register */ + 430:stm32lib/src/stm32f10x_usart.c **** USARTx->CR3 &= (u16)~USART_DMAReq; + 243 .loc 1 430 0 + 244 00b0 838A ldrh r3, [r0, #20] + 245 00b2 9BB2 uxth r3, r3 + 246 00b4 23EA0103 bic r3, r3, r1 + 247 .L24: + 248 00b8 8382 strh r3, [r0, #20] @ movhi + 431:stm32lib/src/stm32f10x_usart.c **** } + 432:stm32lib/src/stm32f10x_usart.c **** } + 249 .loc 1 432 0 + 250 00ba 7047 bx lr + 251 .LFE30: + 253 .align 2 + 254 .global USART_SetAddress + 255 .thumb + 256 .thumb_func + 258 USART_SetAddress: + 259 .LFB31: + 433:stm32lib/src/stm32f10x_usart.c **** + 434:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 435:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_SetAddress + 436:stm32lib/src/stm32f10x_usart.c **** * Description : Sets the address of the USART node. + 437:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 438:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 439:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 440:stm32lib/src/stm32f10x_usart.c **** * - USART_Address: Indicates the address of the USART node. + 441:stm32lib/src/stm32f10x_usart.c **** * Output : None + 442:stm32lib/src/stm32f10x_usart.c **** * Return : None + 443:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 444:stm32lib/src/stm32f10x_usart.c **** void USART_SetAddress(USART_TypeDef* USARTx, u8 USART_Address) + 445:stm32lib/src/stm32f10x_usart.c **** { + 260 .loc 1 445 0 + 261 @ args = 0, pretend = 0, frame = 0 + 262 @ frame_needed = 0, uses_anonymous_args = 0 + 263 @ link register save eliminated. + 264 .LVL17: + 446:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 447:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 448:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ADDRESS(USART_Address)); + 449:stm32lib/src/stm32f10x_usart.c **** + 450:stm32lib/src/stm32f10x_usart.c **** /* Clear the USART address */ + 451:stm32lib/src/stm32f10x_usart.c **** USARTx->CR2 &= CR2_Address_Mask; + 265 .loc 1 451 0 + 266 00bc 038A ldrh r3, [r0, #16] + 267 00be 23F00F03 bic r3, r3, #15 + 268 00c2 1B04 lsls r3, r3, #16 + 269 00c4 1B0C lsrs r3, r3, #16 + 270 00c6 0382 strh r3, [r0, #16] @ movhi + 452:stm32lib/src/stm32f10x_usart.c **** /* Set the USART address node */ + 453:stm32lib/src/stm32f10x_usart.c **** USARTx->CR2 |= USART_Address; + 271 .loc 1 453 0 + 272 00c8 038A ldrh r3, [r0, #16] + 273 00ca 9BB2 uxth r3, r3 + 274 00cc 0B43 orrs r3, r3, r1 + 275 00ce 0382 strh r3, [r0, #16] @ movhi + 454:stm32lib/src/stm32f10x_usart.c **** } + 276 .loc 1 454 0 + 277 00d0 7047 bx lr + 278 .LFE31: + 280 00d2 00BF .align 2 + 281 .global USART_WakeUpConfig + 282 .thumb + 283 .thumb_func + 285 USART_WakeUpConfig: + 286 .LFB32: + 455:stm32lib/src/stm32f10x_usart.c **** + 456:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 457:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_WakeUpConfig + 458:stm32lib/src/stm32f10x_usart.c **** * Description : Selects the USART WakeUp method. + 459:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 460:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 461:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 462:stm32lib/src/stm32f10x_usart.c **** * - USART_WakeUp: specifies the USART wakeup method. + 463:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 464:stm32lib/src/stm32f10x_usart.c **** * - USART_WakeUp_IdleLine: WakeUp by an idle line detection + 465:stm32lib/src/stm32f10x_usart.c **** * - USART_WakeUp_AddressMark: WakeUp by an address mark + 466:stm32lib/src/stm32f10x_usart.c **** * Output : None + 467:stm32lib/src/stm32f10x_usart.c **** * Return : None + 468:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 469:stm32lib/src/stm32f10x_usart.c **** void USART_WakeUpConfig(USART_TypeDef* USARTx, u16 USART_WakeUp) + 470:stm32lib/src/stm32f10x_usart.c **** { + 287 .loc 1 470 0 + 288 @ args = 0, pretend = 0, frame = 0 + 289 @ frame_needed = 0, uses_anonymous_args = 0 + 290 @ link register save eliminated. + 291 .LVL18: + 471:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 472:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 473:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_WAKEUP(USART_WakeUp)); + 474:stm32lib/src/stm32f10x_usart.c **** + 475:stm32lib/src/stm32f10x_usart.c **** USARTx->CR1 &= CR1_WAKE_Mask; + 292 .loc 1 475 0 + 293 00d4 8389 ldrh r3, [r0, #12] + 294 00d6 23F40063 bic r3, r3, #2048 + 295 00da 1B04 lsls r3, r3, #16 + 296 00dc 1B0C lsrs r3, r3, #16 + 297 00de 8381 strh r3, [r0, #12] @ movhi + 476:stm32lib/src/stm32f10x_usart.c **** USARTx->CR1 |= USART_WakeUp; + 298 .loc 1 476 0 + 299 00e0 8389 ldrh r3, [r0, #12] + 300 00e2 9BB2 uxth r3, r3 + 301 00e4 1943 orrs r1, r1, r3 + 302 .LVL19: + 303 00e6 8181 strh r1, [r0, #12] @ movhi + 477:stm32lib/src/stm32f10x_usart.c **** } + 304 .loc 1 477 0 + 305 00e8 7047 bx lr + 306 .LFE32: + 308 00ea 00BF .align 2 + 309 .global USART_ReceiverWakeUpCmd + 310 .thumb + 311 .thumb_func + 313 USART_ReceiverWakeUpCmd: + 314 .LFB33: + 478:stm32lib/src/stm32f10x_usart.c **** + 479:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 480:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_ReceiverWakeUpCmd + 481:stm32lib/src/stm32f10x_usart.c **** * Description : Determines if the USART is in mute mode or not. + 482:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 483:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 484:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 485:stm32lib/src/stm32f10x_usart.c **** * - NewState: new state of the USART mute mode. + 486:stm32lib/src/stm32f10x_usart.c **** * This parameter can be: ENABLE or DISABLE. + 487:stm32lib/src/stm32f10x_usart.c **** * Output : None + 488:stm32lib/src/stm32f10x_usart.c **** * Return : None + 489:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 490:stm32lib/src/stm32f10x_usart.c **** void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState) + 491:stm32lib/src/stm32f10x_usart.c **** { + 315 .loc 1 491 0 + 316 @ args = 0, pretend = 0, frame = 0 + 317 @ frame_needed = 0, uses_anonymous_args = 0 + 318 @ link register save eliminated. + 319 .LVL20: + 492:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 493:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 494:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 495:stm32lib/src/stm32f10x_usart.c **** + 496:stm32lib/src/stm32f10x_usart.c **** if (NewState != DISABLE) + 320 .loc 1 496 0 + 321 00ec 21B1 cbz r1, .L30 + 497:stm32lib/src/stm32f10x_usart.c **** { + 498:stm32lib/src/stm32f10x_usart.c **** /* Enable the USART mute mode by setting the RWU bit in the CR1 register */ + 499:stm32lib/src/stm32f10x_usart.c **** USARTx->CR1 |= CR1_RWU_Set; + 322 .loc 1 499 0 + 323 00ee 8389 ldrh r3, [r0, #12] + 324 00f0 9BB2 uxth r3, r3 + 325 00f2 43F00203 orr r3, r3, #2 + 326 00f6 04E0 b .L33 + 327 .L30: + 500:stm32lib/src/stm32f10x_usart.c **** } + 501:stm32lib/src/stm32f10x_usart.c **** else + 502:stm32lib/src/stm32f10x_usart.c **** { + 503:stm32lib/src/stm32f10x_usart.c **** /* Disable the USART mute mode by clearing the RWU bit in the CR1 register */ + 504:stm32lib/src/stm32f10x_usart.c **** USARTx->CR1 &= CR1_RWU_Reset; + 328 .loc 1 504 0 + 329 00f8 8389 ldrh r3, [r0, #12] + 330 00fa 23F00203 bic r3, r3, #2 + 331 00fe 1B04 lsls r3, r3, #16 + 332 0100 1B0C lsrs r3, r3, #16 + 333 .L33: + 334 0102 8381 strh r3, [r0, #12] @ movhi + 505:stm32lib/src/stm32f10x_usart.c **** } + 506:stm32lib/src/stm32f10x_usart.c **** } + 335 .loc 1 506 0 + 336 0104 7047 bx lr + 337 .LFE33: + 339 0106 00BF .align 2 + 340 .global USART_LINBreakDetectLengthConfig + 341 .thumb + 342 .thumb_func + 344 USART_LINBreakDetectLengthConfig: + 345 .LFB34: + 507:stm32lib/src/stm32f10x_usart.c **** + 508:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 509:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_LINBreakDetectLengthConfig + 510:stm32lib/src/stm32f10x_usart.c **** * Description : Sets the USART LIN Break detection length. + 511:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 512:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 513:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 514:stm32lib/src/stm32f10x_usart.c **** * - USART_LINBreakDetectLength: specifies the LIN break + 515:stm32lib/src/stm32f10x_usart.c **** * detection length. + 516:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 517:stm32lib/src/stm32f10x_usart.c **** * - USART_LINBreakDetectLength_10b: 10-bit break detection + 518:stm32lib/src/stm32f10x_usart.c **** * - USART_LINBreakDetectLength_11b: 11-bit break detection + 519:stm32lib/src/stm32f10x_usart.c **** * Output : None + 520:stm32lib/src/stm32f10x_usart.c **** * Return : None + 521:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 522:stm32lib/src/stm32f10x_usart.c **** void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, u16 USART_LINBreakDetectLength) + 523:stm32lib/src/stm32f10x_usart.c **** { + 346 .loc 1 523 0 + 347 @ args = 0, pretend = 0, frame = 0 + 348 @ frame_needed = 0, uses_anonymous_args = 0 + 349 @ link register save eliminated. + 350 .LVL21: + 524:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 525:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 526:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_LIN_BREAK_DETECT_LENGTH(USART_LINBreakDetectLength)); + 527:stm32lib/src/stm32f10x_usart.c **** + 528:stm32lib/src/stm32f10x_usart.c **** USARTx->CR2 &= CR2_LBDL_Mask; + 351 .loc 1 528 0 + 352 0108 038A ldrh r3, [r0, #16] + 353 010a 23F02003 bic r3, r3, #32 + 354 010e 1B04 lsls r3, r3, #16 + 355 0110 1B0C lsrs r3, r3, #16 + 356 0112 0382 strh r3, [r0, #16] @ movhi + 529:stm32lib/src/stm32f10x_usart.c **** USARTx->CR2 |= USART_LINBreakDetectLength; + 357 .loc 1 529 0 + 358 0114 038A ldrh r3, [r0, #16] + 359 0116 9BB2 uxth r3, r3 + 360 0118 1943 orrs r1, r1, r3 + 361 .LVL22: + 362 011a 0182 strh r1, [r0, #16] @ movhi + 530:stm32lib/src/stm32f10x_usart.c **** } + 363 .loc 1 530 0 + 364 011c 7047 bx lr + 365 .LFE34: + 367 011e 00BF .align 2 + 368 .global USART_LINCmd + 369 .thumb + 370 .thumb_func + 372 USART_LINCmd: + 373 .LFB35: + 531:stm32lib/src/stm32f10x_usart.c **** + 532:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 533:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_LINCmd + 534:stm32lib/src/stm32f10x_usart.c **** * Description : Enables or disables the USART’s LIN mode. + 535:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 536:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 537:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 538:stm32lib/src/stm32f10x_usart.c **** * - NewState: new state of the USART LIN mode. + 539:stm32lib/src/stm32f10x_usart.c **** * This parameter can be: ENABLE or DISABLE. + 540:stm32lib/src/stm32f10x_usart.c **** * Output : None + 541:stm32lib/src/stm32f10x_usart.c **** * Return : None + 542:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 543:stm32lib/src/stm32f10x_usart.c **** void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState) + 544:stm32lib/src/stm32f10x_usart.c **** { + 374 .loc 1 544 0 + 375 @ args = 0, pretend = 0, frame = 0 + 376 @ frame_needed = 0, uses_anonymous_args = 0 + 377 @ link register save eliminated. + 378 .LVL23: + 545:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 546:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 547:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 548:stm32lib/src/stm32f10x_usart.c **** + 549:stm32lib/src/stm32f10x_usart.c **** if (NewState != DISABLE) + 379 .loc 1 549 0 + 380 0120 21B1 cbz r1, .L37 + 550:stm32lib/src/stm32f10x_usart.c **** { + 551:stm32lib/src/stm32f10x_usart.c **** /* Enable the LIN mode by setting the LINEN bit in the CR2 register */ + 552:stm32lib/src/stm32f10x_usart.c **** USARTx->CR2 |= CR2_LINEN_Set; + 381 .loc 1 552 0 + 382 0122 038A ldrh r3, [r0, #16] + 383 0124 9BB2 uxth r3, r3 + 384 0126 43F48043 orr r3, r3, #16384 + 385 012a 04E0 b .L40 + 386 .L37: + 553:stm32lib/src/stm32f10x_usart.c **** } + 554:stm32lib/src/stm32f10x_usart.c **** else + 555:stm32lib/src/stm32f10x_usart.c **** { + 556:stm32lib/src/stm32f10x_usart.c **** /* Disable the LIN mode by clearing the LINEN bit in the CR2 register */ + 557:stm32lib/src/stm32f10x_usart.c **** USARTx->CR2 &= CR2_LINEN_Reset; + 387 .loc 1 557 0 + 388 012c 038A ldrh r3, [r0, #16] + 389 012e 23F48043 bic r3, r3, #16384 + 390 0132 1B04 lsls r3, r3, #16 + 391 0134 1B0C lsrs r3, r3, #16 + 392 .L40: + 393 0136 0382 strh r3, [r0, #16] @ movhi + 558:stm32lib/src/stm32f10x_usart.c **** } + 559:stm32lib/src/stm32f10x_usart.c **** } + 394 .loc 1 559 0 + 395 0138 7047 bx lr + 396 .LFE35: + 398 013a 00BF .align 2 + 399 .global USART_SendData + 400 .thumb + 401 .thumb_func + 403 USART_SendData: + 404 .LFB36: + 560:stm32lib/src/stm32f10x_usart.c **** + 561:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 562:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_SendData + 563:stm32lib/src/stm32f10x_usart.c **** * Description : Transmits single data through the USARTx peripheral. + 564:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 565:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 566:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 567:stm32lib/src/stm32f10x_usart.c **** * - Data: the data to transmit. + 568:stm32lib/src/stm32f10x_usart.c **** * Output : None + 569:stm32lib/src/stm32f10x_usart.c **** * Return : None + 570:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 571:stm32lib/src/stm32f10x_usart.c **** void USART_SendData(USART_TypeDef* USARTx, u16 Data) + 572:stm32lib/src/stm32f10x_usart.c **** { + 405 .loc 1 572 0 + 406 @ args = 0, pretend = 0, frame = 0 + 407 @ frame_needed = 0, uses_anonymous_args = 0 + 408 @ link register save eliminated. + 409 .LVL24: + 573:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 574:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 575:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_DATA(Data)); + 576:stm32lib/src/stm32f10x_usart.c **** + 577:stm32lib/src/stm32f10x_usart.c **** /* Transmit Data */ + 578:stm32lib/src/stm32f10x_usart.c **** USARTx->DR = (Data & (u16)0x01FF); + 410 .loc 1 578 0 + 411 013c C905 lsls r1, r1, #23 + 412 .LVL25: + 413 013e C90D lsrs r1, r1, #23 + 414 0140 8180 strh r1, [r0, #4] @ movhi + 579:stm32lib/src/stm32f10x_usart.c **** } + 415 .loc 1 579 0 + 416 0142 7047 bx lr + 417 .LFE36: + 419 .align 2 + 420 .global USART_ReceiveData + 421 .thumb + 422 .thumb_func + 424 USART_ReceiveData: + 425 .LFB37: + 580:stm32lib/src/stm32f10x_usart.c **** + 581:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 582:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_ReceiveData + 583:stm32lib/src/stm32f10x_usart.c **** * Description : Returns the most recent received data by the USARTx peripheral. + 584:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 585:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 586:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 587:stm32lib/src/stm32f10x_usart.c **** * Output : None + 588:stm32lib/src/stm32f10x_usart.c **** * Return : The received data. + 589:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 590:stm32lib/src/stm32f10x_usart.c **** u16 USART_ReceiveData(USART_TypeDef* USARTx) + 591:stm32lib/src/stm32f10x_usart.c **** { + 426 .loc 1 591 0 + 427 @ args = 0, pretend = 0, frame = 0 + 428 @ frame_needed = 0, uses_anonymous_args = 0 + 429 @ link register save eliminated. + 430 .LVL26: + 592:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 593:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 594:stm32lib/src/stm32f10x_usart.c **** + 595:stm32lib/src/stm32f10x_usart.c **** /* Receive Data */ + 596:stm32lib/src/stm32f10x_usart.c **** return (u16)(USARTx->DR & (u16)0x01FF); + 431 .loc 1 596 0 + 432 0144 8088 ldrh r0, [r0, #4] + 433 .LVL27: + 597:stm32lib/src/stm32f10x_usart.c **** } + 434 .loc 1 597 0 + 435 0146 C005 lsls r0, r0, #23 + 436 0148 C00D lsrs r0, r0, #23 + 437 014a 7047 bx lr + 438 .LFE37: + 440 .align 2 + 441 .global USART_SendBreak + 442 .thumb + 443 .thumb_func + 445 USART_SendBreak: + 446 .LFB38: + 598:stm32lib/src/stm32f10x_usart.c **** + 599:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 600:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_SendBreak + 601:stm32lib/src/stm32f10x_usart.c **** * Description : Transmits break characters. + 602:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 603:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 604:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 605:stm32lib/src/stm32f10x_usart.c **** * Output : None + 606:stm32lib/src/stm32f10x_usart.c **** * Return : None + 607:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 608:stm32lib/src/stm32f10x_usart.c **** void USART_SendBreak(USART_TypeDef* USARTx) + 609:stm32lib/src/stm32f10x_usart.c **** { + 447 .loc 1 609 0 + 448 @ args = 0, pretend = 0, frame = 0 + 449 @ frame_needed = 0, uses_anonymous_args = 0 + 450 @ link register save eliminated. + 451 .LVL28: + 610:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 611:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 612:stm32lib/src/stm32f10x_usart.c **** + 613:stm32lib/src/stm32f10x_usart.c **** /* Send break characters */ + 614:stm32lib/src/stm32f10x_usart.c **** USARTx->CR1 |= CR1_SBK_Set; + 452 .loc 1 614 0 + 453 014c 8389 ldrh r3, [r0, #12] + 454 014e 9BB2 uxth r3, r3 + 455 0150 43F00103 orr r3, r3, #1 + 456 0154 8381 strh r3, [r0, #12] @ movhi + 615:stm32lib/src/stm32f10x_usart.c **** } + 457 .loc 1 615 0 + 458 0156 7047 bx lr + 459 .LFE38: + 461 .align 2 + 462 .global USART_SetGuardTime + 463 .thumb + 464 .thumb_func + 466 USART_SetGuardTime: + 467 .LFB39: + 616:stm32lib/src/stm32f10x_usart.c **** + 617:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 618:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_SetGuardTime + 619:stm32lib/src/stm32f10x_usart.c **** * Description : Sets the specified USART guard time. + 620:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: where x can be 1, 2 or 3 to select the USART + 621:stm32lib/src/stm32f10x_usart.c **** * peripheral. + 622:stm32lib/src/stm32f10x_usart.c **** * Note: The guard time bits are not available for UART4 and UART5. + 623:stm32lib/src/stm32f10x_usart.c **** * - USART_GuardTime: specifies the guard time. + 624:stm32lib/src/stm32f10x_usart.c **** * Output : None + 625:stm32lib/src/stm32f10x_usart.c **** * Return : None + 626:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 627:stm32lib/src/stm32f10x_usart.c **** void USART_SetGuardTime(USART_TypeDef* USARTx, u8 USART_GuardTime) + 628:stm32lib/src/stm32f10x_usart.c **** { + 468 .loc 1 628 0 + 469 @ args = 0, pretend = 0, frame = 0 + 470 @ frame_needed = 0, uses_anonymous_args = 0 + 471 @ link register save eliminated. + 472 .LVL29: + 629:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 630:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_123_PERIPH(USARTx)); + 631:stm32lib/src/stm32f10x_usart.c **** + 632:stm32lib/src/stm32f10x_usart.c **** /* Clear the USART Guard time */ + 633:stm32lib/src/stm32f10x_usart.c **** USARTx->GTPR &= GTPR_LSB_Mask; + 473 .loc 1 633 0 + 474 0158 038B ldrh r3, [r0, #24] + 475 015a DBB2 uxtb r3, r3 + 476 015c 0383 strh r3, [r0, #24] @ movhi + 634:stm32lib/src/stm32f10x_usart.c **** /* Set the USART guard time */ + 635:stm32lib/src/stm32f10x_usart.c **** USARTx->GTPR |= (u16)((u16)USART_GuardTime << 0x08); + 477 .loc 1 635 0 + 478 015e 038B ldrh r3, [r0, #24] + 479 0160 9BB2 uxth r3, r3 + 480 0162 43EA0123 orr r3, r3, r1, lsl #8 + 481 0166 0383 strh r3, [r0, #24] @ movhi + 636:stm32lib/src/stm32f10x_usart.c **** } + 482 .loc 1 636 0 + 483 0168 7047 bx lr + 484 .LFE39: + 486 016a 00BF .align 2 + 487 .global USART_SetPrescaler + 488 .thumb + 489 .thumb_func + 491 USART_SetPrescaler: + 492 .LFB40: + 637:stm32lib/src/stm32f10x_usart.c **** + 638:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 639:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_SetPrescaler + 640:stm32lib/src/stm32f10x_usart.c **** * Description : Sets the system clock prescaler. + 641:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 642:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 643:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 644:stm32lib/src/stm32f10x_usart.c **** * Note: The function is used for IrDA mode with UART4 and UART5. + 645:stm32lib/src/stm32f10x_usart.c **** * - USART_Prescaler: specifies the prescaler clock. + 646:stm32lib/src/stm32f10x_usart.c **** * Output : None + 647:stm32lib/src/stm32f10x_usart.c **** * Return : None + 648:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 649:stm32lib/src/stm32f10x_usart.c **** void USART_SetPrescaler(USART_TypeDef* USARTx, u8 USART_Prescaler) + 650:stm32lib/src/stm32f10x_usart.c **** { + 493 .loc 1 650 0 + 494 @ args = 0, pretend = 0, frame = 0 + 495 @ frame_needed = 0, uses_anonymous_args = 0 + 496 @ link register save eliminated. + 497 .LVL30: + 651:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 652:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 653:stm32lib/src/stm32f10x_usart.c **** + 654:stm32lib/src/stm32f10x_usart.c **** /* Clear the USART prescaler */ + 655:stm32lib/src/stm32f10x_usart.c **** USARTx->GTPR &= GTPR_MSB_Mask; + 498 .loc 1 655 0 + 499 016c 038B ldrh r3, [r0, #24] + 500 016e 03F47F43 and r3, r3, #65280 + 501 0172 0383 strh r3, [r0, #24] @ movhi + 656:stm32lib/src/stm32f10x_usart.c **** /* Set the USART prescaler */ + 657:stm32lib/src/stm32f10x_usart.c **** USARTx->GTPR |= USART_Prescaler; + 502 .loc 1 657 0 + 503 0174 038B ldrh r3, [r0, #24] + 504 0176 9BB2 uxth r3, r3 + 505 0178 0B43 orrs r3, r3, r1 + 506 017a 0383 strh r3, [r0, #24] @ movhi + 658:stm32lib/src/stm32f10x_usart.c **** } + 507 .loc 1 658 0 + 508 017c 7047 bx lr + 509 .LFE40: + 511 017e 00BF .align 2 + 512 .global USART_SmartCardCmd + 513 .thumb + 514 .thumb_func + 516 USART_SmartCardCmd: + 517 .LFB41: + 659:stm32lib/src/stm32f10x_usart.c **** + 660:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 661:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_SmartCardCmd + 662:stm32lib/src/stm32f10x_usart.c **** * Description : Enables or disables the USART’s Smart Card mode. + 663:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: where x can be 1, 2 or 3 to select the USART + 664:stm32lib/src/stm32f10x_usart.c **** * peripheral. + 665:stm32lib/src/stm32f10x_usart.c **** * Note: The Smart Card mode is not available for UART4 and UART5. + 666:stm32lib/src/stm32f10x_usart.c **** * - NewState: new state of the Smart Card mode. + 667:stm32lib/src/stm32f10x_usart.c **** * This parameter can be: ENABLE or DISABLE. + 668:stm32lib/src/stm32f10x_usart.c **** * Output : None + 669:stm32lib/src/stm32f10x_usart.c **** * Return : None + 670:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 671:stm32lib/src/stm32f10x_usart.c **** void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState) + 672:stm32lib/src/stm32f10x_usart.c **** { + 518 .loc 1 672 0 + 519 @ args = 0, pretend = 0, frame = 0 + 520 @ frame_needed = 0, uses_anonymous_args = 0 + 521 @ link register save eliminated. + 522 .LVL31: + 673:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 674:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_123_PERIPH(USARTx)); + 675:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 676:stm32lib/src/stm32f10x_usart.c **** + 677:stm32lib/src/stm32f10x_usart.c **** if (NewState != DISABLE) + 523 .loc 1 677 0 + 524 0180 21B1 cbz r1, .L52 + 678:stm32lib/src/stm32f10x_usart.c **** { + 679:stm32lib/src/stm32f10x_usart.c **** /* Enable the SC mode by setting the SCEN bit in the CR3 register */ + 680:stm32lib/src/stm32f10x_usart.c **** USARTx->CR3 |= CR3_SCEN_Set; + 525 .loc 1 680 0 + 526 0182 838A ldrh r3, [r0, #20] + 527 0184 9BB2 uxth r3, r3 + 528 0186 43F02003 orr r3, r3, #32 + 529 018a 04E0 b .L55 + 530 .L52: + 681:stm32lib/src/stm32f10x_usart.c **** } + 682:stm32lib/src/stm32f10x_usart.c **** else + 683:stm32lib/src/stm32f10x_usart.c **** { + 684:stm32lib/src/stm32f10x_usart.c **** /* Disable the SC mode by clearing the SCEN bit in the CR3 register */ + 685:stm32lib/src/stm32f10x_usart.c **** USARTx->CR3 &= CR3_SCEN_Reset; + 531 .loc 1 685 0 + 532 018c 838A ldrh r3, [r0, #20] + 533 018e 23F02003 bic r3, r3, #32 + 534 0192 1B04 lsls r3, r3, #16 + 535 0194 1B0C lsrs r3, r3, #16 + 536 .L55: + 537 0196 8382 strh r3, [r0, #20] @ movhi + 686:stm32lib/src/stm32f10x_usart.c **** } + 687:stm32lib/src/stm32f10x_usart.c **** } + 538 .loc 1 687 0 + 539 0198 7047 bx lr + 540 .LFE41: + 542 019a 00BF .align 2 + 543 .global USART_SmartCardNACKCmd + 544 .thumb + 545 .thumb_func + 547 USART_SmartCardNACKCmd: + 548 .LFB42: + 688:stm32lib/src/stm32f10x_usart.c **** + 689:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 690:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_SmartCardNACKCmd + 691:stm32lib/src/stm32f10x_usart.c **** * Description : Enables or disables NACK transmission. + 692:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: where x can be 1, 2 or 3 to select the USART + 693:stm32lib/src/stm32f10x_usart.c **** * peripheral. + 694:stm32lib/src/stm32f10x_usart.c **** * Note: The Smart Card mode is not available for UART4 and UART5. + 695:stm32lib/src/stm32f10x_usart.c **** * - NewState: new state of the NACK transmission. + 696:stm32lib/src/stm32f10x_usart.c **** * This parameter can be: ENABLE or DISABLE. + 697:stm32lib/src/stm32f10x_usart.c **** * Output : None + 698:stm32lib/src/stm32f10x_usart.c **** * Return : None + 699:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 700:stm32lib/src/stm32f10x_usart.c **** void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState) + 701:stm32lib/src/stm32f10x_usart.c **** { + 549 .loc 1 701 0 + 550 @ args = 0, pretend = 0, frame = 0 + 551 @ frame_needed = 0, uses_anonymous_args = 0 + 552 @ link register save eliminated. + 553 .LVL32: + 702:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 703:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_123_PERIPH(USARTx)); + 704:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 705:stm32lib/src/stm32f10x_usart.c **** + 706:stm32lib/src/stm32f10x_usart.c **** if (NewState != DISABLE) + 554 .loc 1 706 0 + 555 019c 21B1 cbz r1, .L57 + 707:stm32lib/src/stm32f10x_usart.c **** { + 708:stm32lib/src/stm32f10x_usart.c **** /* Enable the NACK transmission by setting the NACK bit in the CR3 register */ + 709:stm32lib/src/stm32f10x_usart.c **** USARTx->CR3 |= CR3_NACK_Set; + 556 .loc 1 709 0 + 557 019e 838A ldrh r3, [r0, #20] + 558 01a0 9BB2 uxth r3, r3 + 559 01a2 43F01003 orr r3, r3, #16 + 560 01a6 04E0 b .L60 + 561 .L57: + 710:stm32lib/src/stm32f10x_usart.c **** } + 711:stm32lib/src/stm32f10x_usart.c **** else + 712:stm32lib/src/stm32f10x_usart.c **** { + 713:stm32lib/src/stm32f10x_usart.c **** /* Disable the NACK transmission by clearing the NACK bit in the CR3 register */ + 714:stm32lib/src/stm32f10x_usart.c **** USARTx->CR3 &= CR3_NACK_Reset; + 562 .loc 1 714 0 + 563 01a8 838A ldrh r3, [r0, #20] + 564 01aa 23F01003 bic r3, r3, #16 + 565 01ae 1B04 lsls r3, r3, #16 + 566 01b0 1B0C lsrs r3, r3, #16 + 567 .L60: + 568 01b2 8382 strh r3, [r0, #20] @ movhi + 715:stm32lib/src/stm32f10x_usart.c **** } + 716:stm32lib/src/stm32f10x_usart.c **** } + 569 .loc 1 716 0 + 570 01b4 7047 bx lr + 571 .LFE42: + 573 01b6 00BF .align 2 + 574 .global USART_HalfDuplexCmd + 575 .thumb + 576 .thumb_func + 578 USART_HalfDuplexCmd: + 579 .LFB43: + 717:stm32lib/src/stm32f10x_usart.c **** + 718:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 719:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_HalfDuplexCmd + 720:stm32lib/src/stm32f10x_usart.c **** * Description : Enables or disables the USART’s Half Duplex communication. + 721:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 722:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 723:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 724:stm32lib/src/stm32f10x_usart.c **** * - NewState: new state of the USART Communication. + 725:stm32lib/src/stm32f10x_usart.c **** * This parameter can be: ENABLE or DISABLE. + 726:stm32lib/src/stm32f10x_usart.c **** * Output : None + 727:stm32lib/src/stm32f10x_usart.c **** * Return : None + 728:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 729:stm32lib/src/stm32f10x_usart.c **** void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState) + 730:stm32lib/src/stm32f10x_usart.c **** { + 580 .loc 1 730 0 + 581 @ args = 0, pretend = 0, frame = 0 + 582 @ frame_needed = 0, uses_anonymous_args = 0 + 583 @ link register save eliminated. + 584 .LVL33: + 731:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 732:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 733:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 734:stm32lib/src/stm32f10x_usart.c **** + 735:stm32lib/src/stm32f10x_usart.c **** if (NewState != DISABLE) + 585 .loc 1 735 0 + 586 01b8 21B1 cbz r1, .L62 + 736:stm32lib/src/stm32f10x_usart.c **** { + 737:stm32lib/src/stm32f10x_usart.c **** /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */ + 738:stm32lib/src/stm32f10x_usart.c **** USARTx->CR3 |= CR3_HDSEL_Set; + 587 .loc 1 738 0 + 588 01ba 838A ldrh r3, [r0, #20] + 589 01bc 9BB2 uxth r3, r3 + 590 01be 43F00803 orr r3, r3, #8 + 591 01c2 04E0 b .L65 + 592 .L62: + 739:stm32lib/src/stm32f10x_usart.c **** } + 740:stm32lib/src/stm32f10x_usart.c **** else + 741:stm32lib/src/stm32f10x_usart.c **** { + 742:stm32lib/src/stm32f10x_usart.c **** /* Disable the Half-Duplex mode by clearing the HDSEL bit in the CR3 register */ + 743:stm32lib/src/stm32f10x_usart.c **** USARTx->CR3 &= CR3_HDSEL_Reset; + 593 .loc 1 743 0 + 594 01c4 838A ldrh r3, [r0, #20] + 595 01c6 23F00803 bic r3, r3, #8 + 596 01ca 1B04 lsls r3, r3, #16 + 597 01cc 1B0C lsrs r3, r3, #16 + 598 .L65: + 599 01ce 8382 strh r3, [r0, #20] @ movhi + 744:stm32lib/src/stm32f10x_usart.c **** } + 745:stm32lib/src/stm32f10x_usart.c **** } + 600 .loc 1 745 0 + 601 01d0 7047 bx lr + 602 .LFE43: + 604 01d2 00BF .align 2 + 605 .global USART_IrDAConfig + 606 .thumb + 607 .thumb_func + 609 USART_IrDAConfig: + 610 .LFB44: + 746:stm32lib/src/stm32f10x_usart.c **** + 747:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 748:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_IrDAConfig + 749:stm32lib/src/stm32f10x_usart.c **** * Description : Configures the USART’s IrDA interface. + 750:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 751:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 752:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 753:stm32lib/src/stm32f10x_usart.c **** * - USART_IrDAMode: specifies the IrDA mode. + 754:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 755:stm32lib/src/stm32f10x_usart.c **** * - USART_IrDAMode_LowPower + 756:stm32lib/src/stm32f10x_usart.c **** * - USART_IrDAMode_Normal + 757:stm32lib/src/stm32f10x_usart.c **** * Output : None + 758:stm32lib/src/stm32f10x_usart.c **** * Return : None + 759:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 760:stm32lib/src/stm32f10x_usart.c **** void USART_IrDAConfig(USART_TypeDef* USARTx, u16 USART_IrDAMode) + 761:stm32lib/src/stm32f10x_usart.c **** { + 611 .loc 1 761 0 + 612 @ args = 0, pretend = 0, frame = 0 + 613 @ frame_needed = 0, uses_anonymous_args = 0 + 614 @ link register save eliminated. + 615 .LVL34: + 762:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 763:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 764:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_IRDA_MODE(USART_IrDAMode)); + 765:stm32lib/src/stm32f10x_usart.c **** + 766:stm32lib/src/stm32f10x_usart.c **** USARTx->CR3 &= CR3_IRLP_Mask; + 616 .loc 1 766 0 + 617 01d4 838A ldrh r3, [r0, #20] + 618 01d6 23F00403 bic r3, r3, #4 + 619 01da 1B04 lsls r3, r3, #16 + 620 01dc 1B0C lsrs r3, r3, #16 + 621 01de 8382 strh r3, [r0, #20] @ movhi + 767:stm32lib/src/stm32f10x_usart.c **** USARTx->CR3 |= USART_IrDAMode; + 622 .loc 1 767 0 + 623 01e0 838A ldrh r3, [r0, #20] + 624 01e2 9BB2 uxth r3, r3 + 625 01e4 1943 orrs r1, r1, r3 + 626 .LVL35: + 627 01e6 8182 strh r1, [r0, #20] @ movhi + 768:stm32lib/src/stm32f10x_usart.c **** } + 628 .loc 1 768 0 + 629 01e8 7047 bx lr + 630 .LFE44: + 632 01ea 00BF .align 2 + 633 .global USART_IrDACmd + 634 .thumb + 635 .thumb_func + 637 USART_IrDACmd: + 638 .LFB45: + 769:stm32lib/src/stm32f10x_usart.c **** + 770:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 771:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_IrDACmd + 772:stm32lib/src/stm32f10x_usart.c **** * Description : Enables or disables the USART’s IrDA interface. + 773:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 774:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 775:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 776:stm32lib/src/stm32f10x_usart.c **** * - NewState: new state of the IrDA mode. + 777:stm32lib/src/stm32f10x_usart.c **** * This parameter can be: ENABLE or DISABLE. + 778:stm32lib/src/stm32f10x_usart.c **** * Output : None + 779:stm32lib/src/stm32f10x_usart.c **** * Return : None + 780:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 781:stm32lib/src/stm32f10x_usart.c **** void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState) + 782:stm32lib/src/stm32f10x_usart.c **** { + 639 .loc 1 782 0 + 640 @ args = 0, pretend = 0, frame = 0 + 641 @ frame_needed = 0, uses_anonymous_args = 0 + 642 @ link register save eliminated. + 643 .LVL36: + 783:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 784:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 785:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_FUNCTIONAL_STATE(NewState)); + 786:stm32lib/src/stm32f10x_usart.c **** + 787:stm32lib/src/stm32f10x_usart.c **** if (NewState != DISABLE) + 644 .loc 1 787 0 + 645 01ec 21B1 cbz r1, .L69 + 788:stm32lib/src/stm32f10x_usart.c **** { + 789:stm32lib/src/stm32f10x_usart.c **** /* Enable the IrDA mode by setting the IREN bit in the CR3 register */ + 790:stm32lib/src/stm32f10x_usart.c **** USARTx->CR3 |= CR3_IREN_Set; + 646 .loc 1 790 0 + 647 01ee 838A ldrh r3, [r0, #20] + 648 01f0 9BB2 uxth r3, r3 + 649 01f2 43F00203 orr r3, r3, #2 + 650 01f6 04E0 b .L72 + 651 .L69: + 791:stm32lib/src/stm32f10x_usart.c **** } + 792:stm32lib/src/stm32f10x_usart.c **** else + 793:stm32lib/src/stm32f10x_usart.c **** { + 794:stm32lib/src/stm32f10x_usart.c **** /* Disable the IrDA mode by clearing the IREN bit in the CR3 register */ + 795:stm32lib/src/stm32f10x_usart.c **** USARTx->CR3 &= CR3_IREN_Reset; + 652 .loc 1 795 0 + 653 01f8 838A ldrh r3, [r0, #20] + 654 01fa 23F00203 bic r3, r3, #2 + 655 01fe 1B04 lsls r3, r3, #16 + 656 0200 1B0C lsrs r3, r3, #16 + 657 .L72: + 658 0202 8382 strh r3, [r0, #20] @ movhi + 796:stm32lib/src/stm32f10x_usart.c **** } + 797:stm32lib/src/stm32f10x_usart.c **** } + 659 .loc 1 797 0 + 660 0204 7047 bx lr + 661 .LFE45: + 663 0206 00BF .align 2 + 664 .global USART_GetFlagStatus + 665 .thumb + 666 .thumb_func + 668 USART_GetFlagStatus: + 669 .LFB46: + 798:stm32lib/src/stm32f10x_usart.c **** + 799:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 800:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_GetFlagStatus + 801:stm32lib/src/stm32f10x_usart.c **** * Description : Checks whether the specified USART flag is set or not. + 802:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 803:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 804:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 805:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG: specifies the flag to check. + 806:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 807:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG_CTS: CTS Change flag (not available for + 808:stm32lib/src/stm32f10x_usart.c **** * UART4 and UART5) + 809:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG_LBD: LIN Break detection flag + 810:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG_TXE: Transmit data register empty flag + 811:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG_TC: Transmission Complete flag + 812:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG_RXNE: Receive data register not empty flag + 813:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG_IDLE: Idle Line detection flag + 814:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG_ORE: OverRun Error flag + 815:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG_NE: Noise Error flag + 816:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG_FE: Framing Error flag + 817:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG_PE: Parity Error flag + 818:stm32lib/src/stm32f10x_usart.c **** * Output : None + 819:stm32lib/src/stm32f10x_usart.c **** * Return : The new state of USART_FLAG (SET or RESET). + 820:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 821:stm32lib/src/stm32f10x_usart.c **** FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, u16 USART_FLAG) + 822:stm32lib/src/stm32f10x_usart.c **** { + 670 .loc 1 822 0 + 671 @ args = 0, pretend = 0, frame = 0 + 672 @ frame_needed = 0, uses_anonymous_args = 0 + 673 @ link register save eliminated. + 674 .LVL37: + 823:stm32lib/src/stm32f10x_usart.c **** FlagStatus bitstatus = RESET; + 824:stm32lib/src/stm32f10x_usart.c **** + 825:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 826:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 827:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_FLAG(USART_FLAG)); + 828:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_PERIPH_FLAG(USARTx, USART_FLAG)); /* The CTS flag is not available for UART + 829:stm32lib/src/stm32f10x_usart.c **** + 830:stm32lib/src/stm32f10x_usart.c **** if ((USARTx->SR & USART_FLAG) != (u16)RESET) + 675 .loc 1 830 0 + 676 0208 0388 ldrh r3, [r0, #0] + 677 020a 1942 tst r1, r3 + 831:stm32lib/src/stm32f10x_usart.c **** { + 832:stm32lib/src/stm32f10x_usart.c **** bitstatus = SET; + 833:stm32lib/src/stm32f10x_usart.c **** } + 834:stm32lib/src/stm32f10x_usart.c **** else + 835:stm32lib/src/stm32f10x_usart.c **** { + 836:stm32lib/src/stm32f10x_usart.c **** bitstatus = RESET; + 837:stm32lib/src/stm32f10x_usart.c **** } + 838:stm32lib/src/stm32f10x_usart.c **** return bitstatus; + 839:stm32lib/src/stm32f10x_usart.c **** } + 678 .loc 1 839 0 + 679 020c 0CBF ite eq + 680 020e 0020 moveq r0, #0 + 681 0210 0120 movne r0, #1 + 682 .LVL38: + 683 0212 7047 bx lr + 684 .LFE46: + 686 .align 2 + 687 .global USART_ClearFlag + 688 .thumb + 689 .thumb_func + 691 USART_ClearFlag: + 692 .LFB47: + 840:stm32lib/src/stm32f10x_usart.c **** + 841:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 842:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_ClearFlag + 843:stm32lib/src/stm32f10x_usart.c **** * Description : Clears the USARTx's pending flags. + 844:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 845:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 846:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 847:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG: specifies the flag to clear. + 848:stm32lib/src/stm32f10x_usart.c **** * This parameter can be any combination of the following values: + 849:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG_CTS: CTS Change flag (not available for + 850:stm32lib/src/stm32f10x_usart.c **** * UART4 and UART5). + 851:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG_LBD: LIN Break detection flag. + 852:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG_TC: Transmission Complete flag. + 853:stm32lib/src/stm32f10x_usart.c **** * - USART_FLAG_RXNE: Receive data register not empty flag. + 854:stm32lib/src/stm32f10x_usart.c **** * + 855:stm32lib/src/stm32f10x_usart.c **** * Notes: + 856:stm32lib/src/stm32f10x_usart.c **** * - PE (Parity error), FE (Framing error), NE (Noise error), + 857:stm32lib/src/stm32f10x_usart.c **** * ORE (OverRun error) and IDLE (Idle line detected) + 858:stm32lib/src/stm32f10x_usart.c **** * flags are cleared by software sequence: a read + 859:stm32lib/src/stm32f10x_usart.c **** * operation to USART_SR register (USART_GetFlagStatus()) + 860:stm32lib/src/stm32f10x_usart.c **** * followed by a read operation to USART_DR register + 861:stm32lib/src/stm32f10x_usart.c **** * (USART_ReceiveData()). + 862:stm32lib/src/stm32f10x_usart.c **** * - RXNE flag can be also cleared by a read to the + 863:stm32lib/src/stm32f10x_usart.c **** * USART_DR register (USART_ReceiveData()). + 864:stm32lib/src/stm32f10x_usart.c **** * - TC flag can be also cleared by software sequence: a + 865:stm32lib/src/stm32f10x_usart.c **** * read operation to USART_SR register + 866:stm32lib/src/stm32f10x_usart.c **** * (USART_GetFlagStatus()) followed by a write operation + 867:stm32lib/src/stm32f10x_usart.c **** * to USART_DR register (USART_SendData()). + 868:stm32lib/src/stm32f10x_usart.c **** * - TXE flag is cleared only by a write to the USART_DR + 869:stm32lib/src/stm32f10x_usart.c **** * register (USART_SendData()). + 870:stm32lib/src/stm32f10x_usart.c **** * Output : None + 871:stm32lib/src/stm32f10x_usart.c **** * Return : None + 872:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 873:stm32lib/src/stm32f10x_usart.c **** void USART_ClearFlag(USART_TypeDef* USARTx, u16 USART_FLAG) + 874:stm32lib/src/stm32f10x_usart.c **** { + 693 .loc 1 874 0 + 694 @ args = 0, pretend = 0, frame = 0 + 695 @ frame_needed = 0, uses_anonymous_args = 0 + 696 @ link register save eliminated. + 697 .LVL39: + 875:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 876:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 877:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_CLEAR_FLAG(USART_FLAG)); + 878:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_PERIPH_FLAG(USARTx, USART_FLAG)); /* The CTS flag is not available for UART + 879:stm32lib/src/stm32f10x_usart.c **** + 880:stm32lib/src/stm32f10x_usart.c **** USARTx->SR = (u16)~USART_FLAG; + 698 .loc 1 880 0 + 699 0214 C943 mvns r1, r1 + 700 .LVL40: + 701 0216 89B2 uxth r1, r1 + 702 0218 0180 strh r1, [r0, #0] @ movhi + 881:stm32lib/src/stm32f10x_usart.c **** } + 703 .loc 1 881 0 + 704 021a 7047 bx lr + 705 .LFE47: + 707 .align 2 + 708 .global USART_GetITStatus + 709 .thumb + 710 .thumb_func + 712 USART_GetITStatus: + 713 .LFB48: + 882:stm32lib/src/stm32f10x_usart.c **** + 883:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 884:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_GetITStatus + 885:stm32lib/src/stm32f10x_usart.c **** * Description : Checks whether the specified USART interrupt has occurred or not. + 886:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 887:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 888:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 889:stm32lib/src/stm32f10x_usart.c **** * - USART_IT: specifies the USART interrupt source to check. + 890:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 891:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_CTS: CTS change interrupt (not available for + 892:stm32lib/src/stm32f10x_usart.c **** * UART4 and UART5) + 893:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_LBD: LIN Break detection interrupt + 894:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_TXE: Tansmit Data Register empty interrupt + 895:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_TC: Transmission complete interrupt + 896:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_RXNE: Receive Data register not empty + 897:stm32lib/src/stm32f10x_usart.c **** * interrupt + 898:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_IDLE: Idle line detection interrupt + 899:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_ORE: OverRun Error interrupt + 900:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_NE: Noise Error interrupt + 901:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_FE: Framing Error interrupt + 902:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_PE: Parity Error interrupt + 903:stm32lib/src/stm32f10x_usart.c **** * Output : None + 904:stm32lib/src/stm32f10x_usart.c **** * Return : The new state of USART_IT (SET or RESET). + 905:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 906:stm32lib/src/stm32f10x_usart.c **** ITStatus USART_GetITStatus(USART_TypeDef* USARTx, u16 USART_IT) + 907:stm32lib/src/stm32f10x_usart.c **** { + 714 .loc 1 907 0 + 715 @ args = 0, pretend = 0, frame = 0 + 716 @ frame_needed = 0, uses_anonymous_args = 0 + 717 .LVL41: + 908:stm32lib/src/stm32f10x_usart.c **** u32 bitpos = 0x00, itmask = 0x00, usartreg = 0x00; + 909:stm32lib/src/stm32f10x_usart.c **** ITStatus bitstatus = RESET; + 910:stm32lib/src/stm32f10x_usart.c **** + 911:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 912:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 913:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_GET_IT(USART_IT)); + 914:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_PERIPH_IT(USARTx, USART_IT)); /* The CTS interrupt is not available for UAR + 915:stm32lib/src/stm32f10x_usart.c **** + 916:stm32lib/src/stm32f10x_usart.c **** /* Get the USART register index */ + 917:stm32lib/src/stm32f10x_usart.c **** usartreg = (((u8)USART_IT) >> 0x05); + 918:stm32lib/src/stm32f10x_usart.c **** + 919:stm32lib/src/stm32f10x_usart.c **** /* Get the interrupt position */ + 920:stm32lib/src/stm32f10x_usart.c **** itmask = USART_IT & IT_Mask; + 921:stm32lib/src/stm32f10x_usart.c **** + 922:stm32lib/src/stm32f10x_usart.c **** itmask = (u32)0x01 << itmask; + 718 .loc 1 922 0 + 719 021c 0123 movs r3, #1 + 720 .loc 1 907 0 + 721 021e 10B5 push {r4, lr} + 722 .LCFI2: + 723 .loc 1 922 0 + 724 0220 01F01F02 and r2, r1, #31 + 725 .loc 1 907 0 + 726 0224 0446 mov r4, r0 + 727 .loc 1 917 0 + 728 0226 C1F34210 ubfx r0, r1, #5, #3 + 729 .LVL42: + 730 .loc 1 922 0 + 731 022a 13FA02F2 lsls r2, r3, r2 + 732 .LVL43: + 923:stm32lib/src/stm32f10x_usart.c **** + 924:stm32lib/src/stm32f10x_usart.c **** if (usartreg == 0x01) /* The IT is in CR1 register */ + 733 .loc 1 924 0 + 734 022e 9842 cmp r0, r3 + 735 0230 01D1 bne .L78 + 925:stm32lib/src/stm32f10x_usart.c **** { + 926:stm32lib/src/stm32f10x_usart.c **** itmask &= USARTx->CR1; + 736 .loc 1 926 0 + 737 0232 A389 ldrh r3, [r4, #12] + 738 0234 03E0 b .L84 + 739 .L78: + 927:stm32lib/src/stm32f10x_usart.c **** } + 928:stm32lib/src/stm32f10x_usart.c **** else if (usartreg == 0x02) /* The IT is in CR2 register */ + 740 .loc 1 928 0 + 741 0236 0228 cmp r0, #2 + 929:stm32lib/src/stm32f10x_usart.c **** { + 930:stm32lib/src/stm32f10x_usart.c **** itmask &= USARTx->CR2; + 742 .loc 1 930 0 + 743 0238 0CBF ite eq + 744 023a 238A ldrheq r3, [r4, #16] + 931:stm32lib/src/stm32f10x_usart.c **** } + 932:stm32lib/src/stm32f10x_usart.c **** else /* The IT is in CR3 register */ + 933:stm32lib/src/stm32f10x_usart.c **** { + 934:stm32lib/src/stm32f10x_usart.c **** itmask &= USARTx->CR3; + 745 .loc 1 934 0 + 746 023c A38A ldrhne r3, [r4, #20] + 747 .L84: + 748 023e 9BB2 uxth r3, r3 + 749 0240 02EA0300 and r0, r2, r3 + 750 .LVL44: + 935:stm32lib/src/stm32f10x_usart.c **** } + 936:stm32lib/src/stm32f10x_usart.c **** + 937:stm32lib/src/stm32f10x_usart.c **** bitpos = USART_IT >> 0x08; + 938:stm32lib/src/stm32f10x_usart.c **** + 939:stm32lib/src/stm32f10x_usart.c **** bitpos = (u32)0x01 << bitpos; + 940:stm32lib/src/stm32f10x_usart.c **** bitpos &= USARTx->SR; + 751 .loc 1 940 0 + 752 0244 2388 ldrh r3, [r4, #0] + 753 0246 9CB2 uxth r4, r3 + 754 .LVL45: + 941:stm32lib/src/stm32f10x_usart.c **** + 942:stm32lib/src/stm32f10x_usart.c **** if ((itmask != (u16)RESET)&&(bitpos != (u16)RESET)) + 755 .loc 1 942 0 + 756 0248 30B1 cbz r0, .L82 + 757 .loc 1 939 0 + 758 024a 0A0A lsrs r2, r1, #8 + 759 024c 0123 movs r3, #1 + 760 024e 9340 lsls r3, r3, r2 + 761 .LVL46: + 762 0250 2342 tst r3, r4 + 763 0252 0CBF ite eq + 764 0254 0020 moveq r0, #0 + 765 0256 0120 movne r0, #1 + 766 .LVL47: + 767 .L82: + 768 .LVL48: + 943:stm32lib/src/stm32f10x_usart.c **** { + 944:stm32lib/src/stm32f10x_usart.c **** bitstatus = SET; + 945:stm32lib/src/stm32f10x_usart.c **** } + 946:stm32lib/src/stm32f10x_usart.c **** else + 947:stm32lib/src/stm32f10x_usart.c **** { + 948:stm32lib/src/stm32f10x_usart.c **** bitstatus = RESET; + 949:stm32lib/src/stm32f10x_usart.c **** } + 950:stm32lib/src/stm32f10x_usart.c **** + 951:stm32lib/src/stm32f10x_usart.c **** return bitstatus; + 952:stm32lib/src/stm32f10x_usart.c **** } + 769 .loc 1 952 0 + 770 0258 10BD pop {r4, pc} + 771 .LFE48: + 773 025a 00BF .align 2 + 774 .global USART_ClearITPendingBit + 775 .thumb + 776 .thumb_func + 778 USART_ClearITPendingBit: + 779 .LFB49: + 953:stm32lib/src/stm32f10x_usart.c **** + 954:stm32lib/src/stm32f10x_usart.c **** /******************************************************************************* + 955:stm32lib/src/stm32f10x_usart.c **** * Function Name : USART_ClearITPendingBit + 956:stm32lib/src/stm32f10x_usart.c **** * Description : Clears the USARTx’s interrupt pending bits. + 957:stm32lib/src/stm32f10x_usart.c **** * Input : - USARTx: Select the USART or the UART peripheral. + 958:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 959:stm32lib/src/stm32f10x_usart.c **** * - USART1, USART2, USART3, UART4 or UART5. + 960:stm32lib/src/stm32f10x_usart.c **** * - USART_IT: specifies the interrupt pending bit to clear. + 961:stm32lib/src/stm32f10x_usart.c **** * This parameter can be one of the following values: + 962:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_CTS: CTS change interrupt (not available for + 963:stm32lib/src/stm32f10x_usart.c **** * UART4 and UART5) + 964:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_LBD: LIN Break detection interrupt + 965:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_TC: Transmission complete interrupt. + 966:stm32lib/src/stm32f10x_usart.c **** * - USART_IT_RXNE: Receive Data register not empty interrupt. + 967:stm32lib/src/stm32f10x_usart.c **** * + 968:stm32lib/src/stm32f10x_usart.c **** * Notes: + 969:stm32lib/src/stm32f10x_usart.c **** * - PE (Parity error), FE (Framing error), NE (Noise error), + 970:stm32lib/src/stm32f10x_usart.c **** * ORE (OverRun error) and IDLE (Idle line detected) + 971:stm32lib/src/stm32f10x_usart.c **** * pending bits are cleared by software sequence: a read + 972:stm32lib/src/stm32f10x_usart.c **** * operation to USART_SR register (USART_GetITStatus()) + 973:stm32lib/src/stm32f10x_usart.c **** * followed by a read operation to USART_DR register + 974:stm32lib/src/stm32f10x_usart.c **** * (USART_ReceiveData()). + 975:stm32lib/src/stm32f10x_usart.c **** * - RXNE pending bit can be also cleared by a read to the + 976:stm32lib/src/stm32f10x_usart.c **** * USART_DR register (USART_ReceiveData()). + 977:stm32lib/src/stm32f10x_usart.c **** * - TC pending bit can be also cleared by software + 978:stm32lib/src/stm32f10x_usart.c **** * sequence: a read operation to USART_SR register + 979:stm32lib/src/stm32f10x_usart.c **** * (USART_GetITStatus()) followed by a write operation + 980:stm32lib/src/stm32f10x_usart.c **** * to USART_DR register (USART_SendData()). + 981:stm32lib/src/stm32f10x_usart.c **** * - TXE pending bit is cleared only by a write to the + 982:stm32lib/src/stm32f10x_usart.c **** * USART_DR register (USART_SendData()). + 983:stm32lib/src/stm32f10x_usart.c **** * Output : None + 984:stm32lib/src/stm32f10x_usart.c **** * Return : None + 985:stm32lib/src/stm32f10x_usart.c **** *******************************************************************************/ + 986:stm32lib/src/stm32f10x_usart.c **** void USART_ClearITPendingBit(USART_TypeDef* USARTx, u16 USART_IT) + 987:stm32lib/src/stm32f10x_usart.c **** { + 780 .loc 1 987 0 + 781 @ args = 0, pretend = 0, frame = 0 + 782 @ frame_needed = 0, uses_anonymous_args = 0 + 783 @ link register save eliminated. + 784 .LVL49: + 988:stm32lib/src/stm32f10x_usart.c **** u16 bitpos = 0x00, itmask = 0x00; + 989:stm32lib/src/stm32f10x_usart.c **** + 990:stm32lib/src/stm32f10x_usart.c **** /* Check the parameters */ + 991:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_ALL_PERIPH(USARTx)); + 992:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_CLEAR_IT(USART_IT)); + 993:stm32lib/src/stm32f10x_usart.c **** assert_param(IS_USART_PERIPH_IT(USARTx, USART_IT)); /* The CTS interrupt is not available for UAR + 994:stm32lib/src/stm32f10x_usart.c **** + 995:stm32lib/src/stm32f10x_usart.c **** bitpos = USART_IT >> 0x08; + 996:stm32lib/src/stm32f10x_usart.c **** + 997:stm32lib/src/stm32f10x_usart.c **** itmask = (u16)((u16)0x01 << bitpos); + 998:stm32lib/src/stm32f10x_usart.c **** USARTx->SR = (u16)~itmask; + 785 .loc 1 998 0 + 786 025c 090A lsrs r1, r1, #8 + 787 .LVL50: + 788 025e 0123 movs r3, #1 + 789 0260 8B40 lsls r3, r3, r1 + 790 0262 DB43 mvns r3, r3 + 791 0264 9BB2 uxth r3, r3 + 792 0266 0380 strh r3, [r0, #0] @ movhi + 999:stm32lib/src/stm32f10x_usart.c **** } + 793 .loc 1 999 0 + 794 0268 7047 bx lr + 795 .LFE49: + 797 026a 00BF .align 2 + 798 .global USART_Init + 799 .thumb + 800 .thumb_func + 802 USART_Init: + 803 .LFB24: + 804 .loc 1 141 0 + 805 @ args = 0, pretend = 0, frame = 32 + 806 @ frame_needed = 0, uses_anonymous_args = 0 + 807 .LVL51: + 808 .loc 1 162 0 + 809 026c 038A ldrh r3, [r0, #16] + 810 .LVL52: + 811 .loc 1 171 0 + 812 026e CA88 ldrh r2, [r1, #6] + 813 .loc 1 164 0 + 814 0270 23F44053 bic r3, r3, #12288 + 815 .LVL53: + 816 0274 1B04 lsls r3, r3, #16 + 817 0276 1B0C lsrs r3, r3, #16 + 818 .loc 1 171 0 + 819 0278 1343 orrs r3, r3, r2 + 820 .LVL54: + 821 027a 0382 strh r3, [r0, #16] @ movhi + 822 .loc 1 174 0 + 823 027c 8289 ldrh r2, [r0, #12] + 824 .loc 1 186 0 + 825 027e 0B89 ldrh r3, [r1, #8] + 826 .loc 1 141 0 + 827 0280 30B5 push {r4, r5, lr} + 828 .LCFI3: + 829 0282 0D46 mov r5, r1 + 830 .loc 1 186 0 + 831 0284 8988 ldrh r1, [r1, #4] + 832 .LVL55: + 833 .loc 1 176 0 + 834 0286 22F4B052 bic r2, r2, #5632 + 835 .LVL56: + 836 .loc 1 186 0 + 837 028a 0B43 orrs r3, r3, r1 + 838 028c 6989 ldrh r1, [r5, #10] + 839 .loc 1 176 0 + 840 028e 22F00C02 bic r2, r2, #12 + 841 .loc 1 186 0 + 842 0292 0B43 orrs r3, r3, r1 + 843 .loc 1 176 0 + 844 0294 1204 lsls r2, r2, #16 + 845 0296 120C lsrs r2, r2, #16 + 846 .loc 1 186 0 + 847 0298 9BB2 uxth r3, r3 + 848 029a 1343 orrs r3, r3, r2 + 849 029c 8381 strh r3, [r0, #12] @ movhi + 850 .loc 1 189 0 + 851 029e 838A ldrh r3, [r0, #20] + 852 .loc 1 198 0 + 853 02a0 AA89 ldrh r2, [r5, #12] + 854 .LVL57: + 855 .loc 1 191 0 + 856 02a2 23F44073 bic r3, r3, #768 + 857 .LVL58: + 858 02a6 1B04 lsls r3, r3, #16 + 859 02a8 1B0C lsrs r3, r3, #16 + 860 .loc 1 141 0 + 861 02aa 89B0 sub sp, sp, #36 + 862 .LCFI4: + 863 .loc 1 198 0 + 864 02ac 1343 orrs r3, r3, r2 + 865 .LVL59: + 866 .loc 1 162 0 + 867 02ae 0446 mov r4, r0 + 868 .LVL60: + 869 .loc 1 198 0 + 870 02b0 8382 strh r3, [r0, #20] @ movhi + 871 .LVL61: + 872 .loc 1 141 0 + 873 02b2 0190 str r0, [sp, #4] + 874 .LVL62: + 875 .loc 1 202 0 + 876 02b4 03A8 add r0, sp, #12 + 877 .LVL63: + 878 02b6 FFF7FEFF bl RCC_GetClocksFreq + 879 .loc 1 203 0 + 880 02ba 0E4B ldr r3, .L91 + 881 02bc 9C42 cmp r4, r3 + 882 .loc 1 205 0 + 883 02be 0CBF ite eq + 884 02c0 069B ldreq r3, [sp, #24] + 885 .LVL64: + 886 .loc 1 209 0 + 887 02c2 059B ldrne r3, [sp, #20] + 888 .loc 1 213 0 + 889 02c4 1922 movs r2, #25 + 890 02c6 5A43 muls r2, r3, r2 + 891 02c8 2B68 ldr r3, [r5, #0] + 892 .LVL65: + 893 .loc 1 214 0 + 894 02ca 6420 movs r0, #100 + 895 .loc 1 213 0 + 896 02cc 9B00 lsls r3, r3, #2 + 897 02ce B2FBF3F2 udiv r2, r2, r3 + 898 .LVL66: + 899 .loc 1 214 0 + 900 02d2 B2FBF0F1 udiv r1, r2, r0 + 901 02d6 0901 lsls r1, r1, #4 + 902 .LVL67: + 903 .loc 1 218 0 + 904 02d8 0B09 lsrs r3, r1, #4 + 905 02da 00FB1323 mls r3, r0, r3, r2 + 906 02de 1B01 lsls r3, r3, #4 + 907 02e0 3233 adds r3, r3, #50 + 908 02e2 B3FBF0F3 udiv r3, r3, r0 + 909 02e6 03F00F03 and r3, r3, #15 + 910 .loc 1 221 0 + 911 02ea 0B43 orrs r3, r3, r1 + 912 02ec 9BB2 uxth r3, r3 + 913 02ee 2381 strh r3, [r4, #8] @ movhi + 914 .loc 1 222 0 + 915 02f0 09B0 add sp, sp, #36 + 916 02f2 30BD pop {r4, r5, pc} + 917 .L92: + 918 .align 2 + 919 .L91: + 920 02f4 00380140 .word 1073821696 + 921 .LFE24: + 923 .align 2 + 924 .global USART_DeInit + 925 .thumb + 926 .thumb_func + 928 USART_DeInit: + 929 .LFB23: + 930 .loc 1 91 0 + 931 @ args = 0, pretend = 0, frame = 8 + 932 @ frame_needed = 0, uses_anonymous_args = 0 + 933 .LVL68: + 934 02f8 07B5 push {r0, r1, r2, lr} + 935 .LCFI5: + 936 .LVL69: + 937 .loc 1 95 0 + 938 02fa 214B ldr r3, .L104 + 939 .loc 1 91 0 + 940 02fc 0190 str r0, [sp, #4] + 941 .LVL70: + 942 .loc 1 95 0 + 943 02fe 9842 cmp r0, r3 + 944 .LVL71: + 945 0300 2BD0 beq .L97 + 946 0302 08D8 bhi .L100 + 947 0304 A3F50063 sub r3, r3, #2048 + 948 0308 9842 cmp r0, r3 + 949 030a 16D0 beq .L95 + 950 030c 03F58063 add r3, r3, #1024 + 951 0310 9842 cmp r0, r3 + 952 0312 34D1 bne .L101 + 953 0314 19E0 b .L103 + 954 .L100: + 955 0316 1B4B ldr r3, .L104+4 + 956 0318 9842 cmp r0, r3 + 957 031a 26D0 beq .L98 + 958 031c 03F56843 add r3, r3, #59392 + 959 0320 9842 cmp r0, r3 + 960 0322 2CD1 bne .L101 + 961 .loc 1 98 0 + 962 0324 0121 movs r1, #1 + 963 0326 4FF48040 mov r0, #16384 + 964 032a FFF7FEFF bl RCC_APB2PeriphResetCmd + 965 .loc 1 99 0 + 966 032e 4FF48040 mov r0, #16384 + 967 0332 0021 movs r1, #0 + 968 0334 FFF7FEFF bl RCC_APB2PeriphResetCmd + 969 0338 21E0 b .L101 + 970 .L95: + 971 .loc 1 103 0 + 972 033a 4FF40030 mov r0, #131072 + 973 033e 0121 movs r1, #1 + 974 0340 FFF7FEFF bl RCC_APB1PeriphResetCmd + 975 .loc 1 104 0 + 976 0344 4FF40030 mov r0, #131072 + 977 0348 16E0 b .L102 + 978 .L103: + 979 .loc 1 108 0 + 980 034a 4FF48020 mov r0, #262144 + 981 034e 0121 movs r1, #1 + 982 0350 FFF7FEFF bl RCC_APB1PeriphResetCmd + 983 .loc 1 109 0 + 984 0354 4FF48020 mov r0, #262144 + 985 0358 0EE0 b .L102 + 986 .L97: + 987 .loc 1 113 0 + 988 035a 4FF40020 mov r0, #524288 + 989 035e 0121 movs r1, #1 + 990 0360 FFF7FEFF bl RCC_APB1PeriphResetCmd + 991 .loc 1 114 0 + 992 0364 4FF40020 mov r0, #524288 + 993 0368 06E0 b .L102 + 994 .L98: + 995 .loc 1 118 0 + 996 036a 4FF48010 mov r0, #1048576 + 997 036e 0121 movs r1, #1 + 998 0370 FFF7FEFF bl RCC_APB1PeriphResetCmd + 999 .loc 1 119 0 + 1000 0374 4FF48010 mov r0, #1048576 + 1001 .L102: + 1002 0378 0021 movs r1, #0 + 1003 037a FFF7FEFF bl RCC_APB1PeriphResetCmd + 1004 .L101: + 1005 .loc 1 125 0 + 1006 037e 0EBD pop {r1, r2, r3, pc} + 1007 .L105: + 1008 .align 2 + 1009 .L104: + 1010 0380 004C0040 .word 1073761280 + 1011 0384 00500040 .word 1073762304 + 1012 .LFE23: + 1292 .Letext0: +DEFINED SYMBOLS + *ABS*:00000000 stm32f10x_usart.c + /tmp/ccXtCsdz.s:22 .text:00000000 $t + /tmp/ccXtCsdz.s:27 .text:00000000 USART_StructInit + /tmp/ccXtCsdz.s:60 .text:0000001c USART_ClockInit + /tmp/ccXtCsdz.s:104 .text:00000040 USART_ClockStructInit + /tmp/ccXtCsdz.s:129 .text:0000004c USART_Cmd + /tmp/ccXtCsdz.s:160 .text:00000068 USART_ITConfig + /tmp/ccXtCsdz.s:228 .text:000000a4 USART_DMACmd + /tmp/ccXtCsdz.s:258 .text:000000bc USART_SetAddress + /tmp/ccXtCsdz.s:285 .text:000000d4 USART_WakeUpConfig + /tmp/ccXtCsdz.s:313 .text:000000ec USART_ReceiverWakeUpCmd + /tmp/ccXtCsdz.s:344 .text:00000108 USART_LINBreakDetectLengthConfig + /tmp/ccXtCsdz.s:372 .text:00000120 USART_LINCmd + /tmp/ccXtCsdz.s:403 .text:0000013c USART_SendData + /tmp/ccXtCsdz.s:424 .text:00000144 USART_ReceiveData + /tmp/ccXtCsdz.s:445 .text:0000014c USART_SendBreak + /tmp/ccXtCsdz.s:466 .text:00000158 USART_SetGuardTime + /tmp/ccXtCsdz.s:491 .text:0000016c USART_SetPrescaler + /tmp/ccXtCsdz.s:516 .text:00000180 USART_SmartCardCmd + /tmp/ccXtCsdz.s:547 .text:0000019c USART_SmartCardNACKCmd + /tmp/ccXtCsdz.s:578 .text:000001b8 USART_HalfDuplexCmd + /tmp/ccXtCsdz.s:609 .text:000001d4 USART_IrDAConfig + /tmp/ccXtCsdz.s:637 .text:000001ec USART_IrDACmd + /tmp/ccXtCsdz.s:668 .text:00000208 USART_GetFlagStatus + /tmp/ccXtCsdz.s:691 .text:00000214 USART_ClearFlag + /tmp/ccXtCsdz.s:712 .text:0000021c USART_GetITStatus + /tmp/ccXtCsdz.s:778 .text:0000025c USART_ClearITPendingBit + /tmp/ccXtCsdz.s:802 .text:0000026c USART_Init + /tmp/ccXtCsdz.s:920 .text:000002f4 $d + /tmp/ccXtCsdz.s:923 .text:000002f8 $t + /tmp/ccXtCsdz.s:928 .text:000002f8 USART_DeInit + /tmp/ccXtCsdz.s:1010 .text:00000380 $d + +UNDEFINED SYMBOLS +RCC_GetClocksFreq +RCC_APB2PeriphResetCmd +RCC_APB1PeriphResetCmd diff --git a/src/stm32lib/src/stm32f10x_wwdg.c b/src/stm32lib/src/stm32f10x_wwdg.c new file mode 100644 index 0000000..ac9882f --- /dev/null +++ b/src/stm32lib/src/stm32f10x_wwdg.c @@ -0,0 +1,185 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
+* File Name : stm32f10x_wwdg.c
+* Author : MCD Application Team
+* Version : V2.0.2
+* Date : 07/11/2008
+* Description : This file provides all the WWDG firmware functions.
+********************************************************************************
+* 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.
+*******************************************************************************/
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_wwdg.h"
+#include "stm32f10x_rcc.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ----------- WWDG registers bit address in the alias region ----------- */
+#define WWDG_OFFSET (WWDG_BASE - PERIPH_BASE)
+
+/* Alias word address of EWI bit */
+#define CFR_OFFSET (WWDG_OFFSET + 0x04)
+#define EWI_BitNumber 0x09
+#define CFR_EWI_BB (PERIPH_BB_BASE + (CFR_OFFSET * 32) + (EWI_BitNumber * 4))
+
+/* --------------------- WWDG registers bit mask ------------------------ */
+/* CR register bit mask */
+#define CR_WDGA_Set ((u32)0x00000080)
+
+/* CFR register bit mask */
+#define CFR_WDGTB_Mask ((u32)0xFFFFFE7F)
+#define CFR_W_Mask ((u32)0xFFFFFF80)
+
+#define BIT_Mask ((u8)0x7F)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/*******************************************************************************
+* Function Name : WWDG_DeInit
+* Description : Deinitializes the WWDG peripheral registers to their default
+* reset values.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_DeInit(void)
+{
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, ENABLE);
+ RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, DISABLE);
+}
+
+/*******************************************************************************
+* Function Name : WWDG_SetPrescaler
+* Description : Sets the WWDG Prescaler.
+* Input : - WWDG_Prescaler: specifies the WWDG Prescaler.
+* This parameter can be one of the following values:
+* - WWDG_Prescaler_1: WWDG counter clock = (PCLK1/4096)/1
+* - WWDG_Prescaler_2: WWDG counter clock = (PCLK1/4096)/2
+* - WWDG_Prescaler_4: WWDG counter clock = (PCLK1/4096)/4
+* - WWDG_Prescaler_8: WWDG counter clock = (PCLK1/4096)/8
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_SetPrescaler(u32 WWDG_Prescaler)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_WWDG_PRESCALER(WWDG_Prescaler));
+
+ /* Clear WDGTB[1:0] bits */
+ tmpreg = WWDG->CFR & CFR_WDGTB_Mask;
+
+ /* Set WDGTB[1:0] bits according to WWDG_Prescaler value */
+ tmpreg |= WWDG_Prescaler;
+
+ /* Store the new value */
+ WWDG->CFR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : WWDG_SetWindowValue
+* Description : Sets the WWDG window value.
+* Input : - WindowValue: specifies the window value to be compared to
+* the downcounter.
+* This parameter value must be lower than 0x80.
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_SetWindowValue(u8 WindowValue)
+{
+ u32 tmpreg = 0;
+
+ /* Check the parameters */
+ assert_param(IS_WWDG_WINDOW_VALUE(WindowValue));
+
+ /* Clear W[6:0] bits */
+ tmpreg = WWDG->CFR & CFR_W_Mask;
+
+ /* Set W[6:0] bits according to WindowValue value */
+ tmpreg |= WindowValue & BIT_Mask;
+
+ /* Store the new value */
+ WWDG->CFR = tmpreg;
+}
+
+/*******************************************************************************
+* Function Name : WWDG_EnableIT
+* Description : Enables the WWDG Early Wakeup interrupt(EWI).
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_EnableIT(void)
+{
+ *(vu32 *) CFR_EWI_BB = (u32)ENABLE;
+}
+
+/*******************************************************************************
+* Function Name : WWDG_SetCounter
+* Description : Sets the WWDG counter value.
+* Input : - Counter: specifies the watchdog counter value.
+* This parameter must be a number between 0x40 and 0x7F.
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_SetCounter(u8 Counter)
+{
+ /* Check the parameters */
+ assert_param(IS_WWDG_COUNTER(Counter));
+
+ /* Write to T[6:0] bits to configure the counter value, no need to do
+ a read-modify-write; writing a 0 to WDGA bit does nothing */
+ WWDG->CR = Counter & BIT_Mask;
+}
+
+/*******************************************************************************
+* Function Name : WWDG_Enable
+* Description : Enables WWDG and load the counter value.
+* - Counter: specifies the watchdog counter value.
+* This parameter must be a number between 0x40 and 0x7F.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_Enable(u8 Counter)
+{
+ /* Check the parameters */
+ assert_param(IS_WWDG_COUNTER(Counter));
+
+ WWDG->CR = CR_WDGA_Set | Counter;
+}
+
+/*******************************************************************************
+* Function Name : WWDG_GetFlagStatus
+* Description : Checks whether the Early Wakeup interrupt flag is set or not.
+* Input : None
+* Output : None
+* Return : The new state of the Early Wakeup interrupt flag (SET or RESET)
+*******************************************************************************/
+FlagStatus WWDG_GetFlagStatus(void)
+{
+ return (FlagStatus)(WWDG->SR);
+}
+
+/*******************************************************************************
+* Function Name : WWDG_ClearFlag
+* Description : Clears Early Wakeup interrupt flag.
+* Input : None
+* Output : None
+* Return : None
+*******************************************************************************/
+void WWDG_ClearFlag(void)
+{
+ WWDG->SR = (u32)RESET;
+}
+
+/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
diff --git a/src/wiring/Print.cpp b/src/wiring/Print.cpp new file mode 100644 index 0000000..20f5e40 --- /dev/null +++ b/src/wiring/Print.cpp @@ -0,0 +1,215 @@ +/* + Print.cpp - Base class that provides print() and println() + Copyright (c) 2008 David A. Mellis. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + + Modified 23 November 2006 by David A. Mellis + */ + +#include <stdio.h> +#include <string.h> +#include <math.h> +#include "wiring.h" + +#include "Print.h" + +// Public Methods ////////////////////////////////////////////////////////////// + +/* default implementation: may be overridden */ +void Print::write(const char *str) +{ + while (*str) + write(*str++); +} + +/* default implementation: may be overridden */ +void Print::write(const uint8_t *buffer, size_t size) +{ + while (size--) + write(*buffer++); +} + +void Print::print(uint8_t b) +{ + this->write(b); +} + +void Print::print(char c) +{ + print((byte) c); +} + +void Print::print(const char str[]) +{ + write(str); +} + +void Print::print(int n) +{ + print((long) n); +} + +void Print::print(unsigned int n) +{ + print((unsigned long) n); +} + +void Print::print(long n) +{ + if (n < 0) { + print('-'); + n = -n; + } + printNumber(n, 10); +} + +void Print::print(unsigned long n) +{ + printNumber(n, 10); +} + +void Print::print(long n, int base) +{ + if (base == 0) + print((char) n); + else if (base == 10) + print(n); + else + printNumber(n, base); +} + +void Print::print(double n) +{ + printFloat(n, 2); +} + +void Print::println(void) +{ + print('\r'); + print('\n'); +} + +void Print::println(char c) +{ + print(c); + println(); +} + +void Print::println(const char c[]) +{ + print(c); + println(); +} + +void Print::println(uint8_t b) +{ + print(b); + println(); +} + +void Print::println(int n) +{ + print(n); + println(); +} + +void Print::println(unsigned int n) +{ + print(n); + println(); +} + +void Print::println(long n) +{ + print(n); + println(); +} + +void Print::println(unsigned long n) +{ + print(n); + println(); +} + +void Print::println(long n, int base) +{ + print(n, base); + println(); +} + +void Print::println(double n) +{ + print(n); + println(); +} + +// Private Methods ///////////////////////////////////////////////////////////// + +void Print::printNumber(unsigned long n, uint8_t base) +{ + unsigned char buf[8 * sizeof(long)]; // Assumes 8-bit chars. + unsigned long i = 0; + + if (n == 0) { + print('0'); + return; + } + + while (n > 0) { + buf[i++] = n % base; + n /= base; + } + + for (; i > 0; i--) + print((char) (buf[i - 1] < 10 ? + '0' + buf[i - 1] : + 'A' + buf[i - 1] - 10)); +} + +void Print::printFloat(double number, uint8_t digits) +{ + // Handle negative numbers + if (number < 0.0) + { + print('-'); + number = -number; + } + + // Round correctly so that print(1.999, 2) prints as "2.00" + double rounding = 0.5; + for (uint8_t i=0; i<digits; ++i) + rounding /= 10.0; + + number += rounding; + + // Extract the integer part of the number and print it + unsigned long int_part = (unsigned long)number; + double remainder = number - (double)int_part; + print(int_part); + + // Print the decimal point, but only if there are digits beyond + if (digits > 0) + print("."); + + // Extract digits from the remainder one at a time + while (digits-- > 0) + { + remainder *= 10.0; + int toPrint = int(remainder); + print(toPrint); + remainder -= toPrint; + } +} diff --git a/src/wiring/Print.h b/src/wiring/Print.h new file mode 100644 index 0000000..a69e85d --- /dev/null +++ b/src/wiring/Print.h @@ -0,0 +1,62 @@ +/* + Print.h - Base class that provides print() and println() + Copyright (c) 2008 David A. Mellis. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef Print_h +#define Print_h + +#include <inttypes.h> +#include <stdio.h> // for size_t + +#define DEC 10 +#define HEX 16 +#define OCT 8 +#define BIN 2 +#define BYTE 0 + +class Print +{ + private: + void printNumber(unsigned long, uint8_t); + void printFloat(double, uint8_t); + public: + virtual void write(uint8_t) = 0; + virtual void write(const char *str); + virtual void write(const uint8_t *buffer, size_t size); + void print(char); + void print(const char[]); + void print(uint8_t); + void print(int); + void print(unsigned int); + void print(long); + void print(unsigned long); + void print(long, int); + void print(double); + void println(void); + void println(char); + void println(const char[]); + void println(uint8_t); + void println(int); + void println(unsigned int); + void println(long); + void println(unsigned long); + void println(long, int); + void println(double); +}; + +#endif diff --git a/src/wiring/binary.h b/src/wiring/binary.h new file mode 100644 index 0000000..af14980 --- /dev/null +++ b/src/wiring/binary.h @@ -0,0 +1,515 @@ +#ifndef Binary_h +#define Binary_h + +#define B0 0 +#define B00 0 +#define B000 0 +#define B0000 0 +#define B00000 0 +#define B000000 0 +#define B0000000 0 +#define B00000000 0 +#define B1 1 +#define B01 1 +#define B001 1 +#define B0001 1 +#define B00001 1 +#define B000001 1 +#define B0000001 1 +#define B00000001 1 +#define B10 2 +#define B010 2 +#define B0010 2 +#define B00010 2 +#define B000010 2 +#define B0000010 2 +#define B00000010 2 +#define B11 3 +#define B011 3 +#define B0011 3 +#define B00011 3 +#define B000011 3 +#define B0000011 3 +#define B00000011 3 +#define B100 4 +#define B0100 4 +#define B00100 4 +#define B000100 4 +#define B0000100 4 +#define B00000100 4 +#define B101 5 +#define B0101 5 +#define B00101 5 +#define B000101 5 +#define B0000101 5 +#define B00000101 5 +#define B110 6 +#define B0110 6 +#define B00110 6 +#define B000110 6 +#define B0000110 6 +#define B00000110 6 +#define B111 7 +#define B0111 7 +#define B00111 7 +#define B000111 7 +#define B0000111 7 +#define B00000111 7 +#define B1000 8 +#define B01000 8 +#define B001000 8 +#define B0001000 8 +#define B00001000 8 +#define B1001 9 +#define B01001 9 +#define B001001 9 +#define B0001001 9 +#define B00001001 9 +#define B1010 10 +#define B01010 10 +#define B001010 10 +#define B0001010 10 +#define B00001010 10 +#define B1011 11 +#define B01011 11 +#define B001011 11 +#define B0001011 11 +#define B00001011 11 +#define B1100 12 +#define B01100 12 +#define B001100 12 +#define B0001100 12 +#define B00001100 12 +#define B1101 13 +#define B01101 13 +#define B001101 13 +#define B0001101 13 +#define B00001101 13 +#define B1110 14 +#define B01110 14 +#define B001110 14 +#define B0001110 14 +#define B00001110 14 +#define B1111 15 +#define B01111 15 +#define B001111 15 +#define B0001111 15 +#define B00001111 15 +#define B10000 16 +#define B010000 16 +#define B0010000 16 +#define B00010000 16 +#define B10001 17 +#define B010001 17 +#define B0010001 17 +#define B00010001 17 +#define B10010 18 +#define B010010 18 +#define B0010010 18 +#define B00010010 18 +#define B10011 19 +#define B010011 19 +#define B0010011 19 +#define B00010011 19 +#define B10100 20 +#define B010100 20 +#define B0010100 20 +#define B00010100 20 +#define B10101 21 +#define B010101 21 +#define B0010101 21 +#define B00010101 21 +#define B10110 22 +#define B010110 22 +#define B0010110 22 +#define B00010110 22 +#define B10111 23 +#define B010111 23 +#define B0010111 23 +#define B00010111 23 +#define B11000 24 +#define B011000 24 +#define B0011000 24 +#define B00011000 24 +#define B11001 25 +#define B011001 25 +#define B0011001 25 +#define B00011001 25 +#define B11010 26 +#define B011010 26 +#define B0011010 26 +#define B00011010 26 +#define B11011 27 +#define B011011 27 +#define B0011011 27 +#define B00011011 27 +#define B11100 28 +#define B011100 28 +#define B0011100 28 +#define B00011100 28 +#define B11101 29 +#define B011101 29 +#define B0011101 29 +#define B00011101 29 +#define B11110 30 +#define B011110 30 +#define B0011110 30 +#define B00011110 30 +#define B11111 31 +#define B011111 31 +#define B0011111 31 +#define B00011111 31 +#define B100000 32 +#define B0100000 32 +#define B00100000 32 +#define B100001 33 +#define B0100001 33 +#define B00100001 33 +#define B100010 34 +#define B0100010 34 +#define B00100010 34 +#define B100011 35 +#define B0100011 35 +#define B00100011 35 +#define B100100 36 +#define B0100100 36 +#define B00100100 36 +#define B100101 37 +#define B0100101 37 +#define B00100101 37 +#define B100110 38 +#define B0100110 38 +#define B00100110 38 +#define B100111 39 +#define B0100111 39 +#define B00100111 39 +#define B101000 40 +#define B0101000 40 +#define B00101000 40 +#define B101001 41 +#define B0101001 41 +#define B00101001 41 +#define B101010 42 +#define B0101010 42 +#define B00101010 42 +#define B101011 43 +#define B0101011 43 +#define B00101011 43 +#define B101100 44 +#define B0101100 44 +#define B00101100 44 +#define B101101 45 +#define B0101101 45 +#define B00101101 45 +#define B101110 46 +#define B0101110 46 +#define B00101110 46 +#define B101111 47 +#define B0101111 47 +#define B00101111 47 +#define B110000 48 +#define B0110000 48 +#define B00110000 48 +#define B110001 49 +#define B0110001 49 +#define B00110001 49 +#define B110010 50 +#define B0110010 50 +#define B00110010 50 +#define B110011 51 +#define B0110011 51 +#define B00110011 51 +#define B110100 52 +#define B0110100 52 +#define B00110100 52 +#define B110101 53 +#define B0110101 53 +#define B00110101 53 +#define B110110 54 +#define B0110110 54 +#define B00110110 54 +#define B110111 55 +#define B0110111 55 +#define B00110111 55 +#define B111000 56 +#define B0111000 56 +#define B00111000 56 +#define B111001 57 +#define B0111001 57 +#define B00111001 57 +#define B111010 58 +#define B0111010 58 +#define B00111010 58 +#define B111011 59 +#define B0111011 59 +#define B00111011 59 +#define B111100 60 +#define B0111100 60 +#define B00111100 60 +#define B111101 61 +#define B0111101 61 +#define B00111101 61 +#define B111110 62 +#define B0111110 62 +#define B00111110 62 +#define B111111 63 +#define B0111111 63 +#define B00111111 63 +#define B1000000 64 +#define B01000000 64 +#define B1000001 65 +#define B01000001 65 +#define B1000010 66 +#define B01000010 66 +#define B1000011 67 +#define B01000011 67 +#define B1000100 68 +#define B01000100 68 +#define B1000101 69 +#define B01000101 69 +#define B1000110 70 +#define B01000110 70 +#define B1000111 71 +#define B01000111 71 +#define B1001000 72 +#define B01001000 72 +#define B1001001 73 +#define B01001001 73 +#define B1001010 74 +#define B01001010 74 +#define B1001011 75 +#define B01001011 75 +#define B1001100 76 +#define B01001100 76 +#define B1001101 77 +#define B01001101 77 +#define B1001110 78 +#define B01001110 78 +#define B1001111 79 +#define B01001111 79 +#define B1010000 80 +#define B01010000 80 +#define B1010001 81 +#define B01010001 81 +#define B1010010 82 +#define B01010010 82 +#define B1010011 83 +#define B01010011 83 +#define B1010100 84 +#define B01010100 84 +#define B1010101 85 +#define B01010101 85 +#define B1010110 86 +#define B01010110 86 +#define B1010111 87 +#define B01010111 87 +#define B1011000 88 +#define B01011000 88 +#define B1011001 89 +#define B01011001 89 +#define B1011010 90 +#define B01011010 90 +#define B1011011 91 +#define B01011011 91 +#define B1011100 92 +#define B01011100 92 +#define B1011101 93 +#define B01011101 93 +#define B1011110 94 +#define B01011110 94 +#define B1011111 95 +#define B01011111 95 +#define B1100000 96 +#define B01100000 96 +#define B1100001 97 +#define B01100001 97 +#define B1100010 98 +#define B01100010 98 +#define B1100011 99 +#define B01100011 99 +#define B1100100 100 +#define B01100100 100 +#define B1100101 101 +#define B01100101 101 +#define B1100110 102 +#define B01100110 102 +#define B1100111 103 +#define B01100111 103 +#define B1101000 104 +#define B01101000 104 +#define B1101001 105 +#define B01101001 105 +#define B1101010 106 +#define B01101010 106 +#define B1101011 107 +#define B01101011 107 +#define B1101100 108 +#define B01101100 108 +#define B1101101 109 +#define B01101101 109 +#define B1101110 110 +#define B01101110 110 +#define B1101111 111 +#define B01101111 111 +#define B1110000 112 +#define B01110000 112 +#define B1110001 113 +#define B01110001 113 +#define B1110010 114 +#define B01110010 114 +#define B1110011 115 +#define B01110011 115 +#define B1110100 116 +#define B01110100 116 +#define B1110101 117 +#define B01110101 117 +#define B1110110 118 +#define B01110110 118 +#define B1110111 119 +#define B01110111 119 +#define B1111000 120 +#define B01111000 120 +#define B1111001 121 +#define B01111001 121 +#define B1111010 122 +#define B01111010 122 +#define B1111011 123 +#define B01111011 123 +#define B1111100 124 +#define B01111100 124 +#define B1111101 125 +#define B01111101 125 +#define B1111110 126 +#define B01111110 126 +#define B1111111 127 +#define B01111111 127 +#define B10000000 128 +#define B10000001 129 +#define B10000010 130 +#define B10000011 131 +#define B10000100 132 +#define B10000101 133 +#define B10000110 134 +#define B10000111 135 +#define B10001000 136 +#define B10001001 137 +#define B10001010 138 +#define B10001011 139 +#define B10001100 140 +#define B10001101 141 +#define B10001110 142 +#define B10001111 143 +#define B10010000 144 +#define B10010001 145 +#define B10010010 146 +#define B10010011 147 +#define B10010100 148 +#define B10010101 149 +#define B10010110 150 +#define B10010111 151 +#define B10011000 152 +#define B10011001 153 +#define B10011010 154 +#define B10011011 155 +#define B10011100 156 +#define B10011101 157 +#define B10011110 158 +#define B10011111 159 +#define B10100000 160 +#define B10100001 161 +#define B10100010 162 +#define B10100011 163 +#define B10100100 164 +#define B10100101 165 +#define B10100110 166 +#define B10100111 167 +#define B10101000 168 +#define B10101001 169 +#define B10101010 170 +#define B10101011 171 +#define B10101100 172 +#define B10101101 173 +#define B10101110 174 +#define B10101111 175 +#define B10110000 176 +#define B10110001 177 +#define B10110010 178 +#define B10110011 179 +#define B10110100 180 +#define B10110101 181 +#define B10110110 182 +#define B10110111 183 +#define B10111000 184 +#define B10111001 185 +#define B10111010 186 +#define B10111011 187 +#define B10111100 188 +#define B10111101 189 +#define B10111110 190 +#define B10111111 191 +#define B11000000 192 +#define B11000001 193 +#define B11000010 194 +#define B11000011 195 +#define B11000100 196 +#define B11000101 197 +#define B11000110 198 +#define B11000111 199 +#define B11001000 200 +#define B11001001 201 +#define B11001010 202 +#define B11001011 203 +#define B11001100 204 +#define B11001101 205 +#define B11001110 206 +#define B11001111 207 +#define B11010000 208 +#define B11010001 209 +#define B11010010 210 +#define B11010011 211 +#define B11010100 212 +#define B11010101 213 +#define B11010110 214 +#define B11010111 215 +#define B11011000 216 +#define B11011001 217 +#define B11011010 218 +#define B11011011 219 +#define B11011100 220 +#define B11011101 221 +#define B11011110 222 +#define B11011111 223 +#define B11100000 224 +#define B11100001 225 +#define B11100010 226 +#define B11100011 227 +#define B11100100 228 +#define B11100101 229 +#define B11100110 230 +#define B11100111 231 +#define B11101000 232 +#define B11101001 233 +#define B11101010 234 +#define B11101011 235 +#define B11101100 236 +#define B11101101 237 +#define B11101110 238 +#define B11101111 239 +#define B11110000 240 +#define B11110001 241 +#define B11110010 242 +#define B11110011 243 +#define B11110100 244 +#define B11110101 245 +#define B11110110 246 +#define B11110111 247 +#define B11111000 248 +#define B11111001 249 +#define B11111010 250 +#define B11111011 251 +#define B11111100 252 +#define B11111101 253 +#define B11111110 254 +#define B11111111 255 + +#endif diff --git a/src/wiring/bits.h b/src/wiring/bits.h new file mode 100644 index 0000000..e614094 --- /dev/null +++ b/src/wiring/bits.h @@ -0,0 +1,35 @@ +// BIT DEFINITION
+
+#define BIT0 0x00000001
+#define BIT1 0x00000002
+#define BIT2 0x00000004
+#define BIT3 0x00000008
+#define BIT4 0x00000010
+#define BIT5 0x00000020
+#define BIT6 0x00000040
+#define BIT7 0x00000080
+#define BIT8 0x00000100
+#define BIT9 0x00000200
+#define BIT10 0x00000400
+#define BIT11 0x00000800
+#define BIT12 0x00001000
+#define BIT13 0x00002000
+#define BIT14 0x00004000
+#define BIT15 0x00008000
+#define BIT16 0x00010000
+#define BIT17 0x00020000
+#define BIT18 0x00040000
+#define BIT19 0x00080000
+#define BIT20 0x00100000
+#define BIT21 0x00200000
+#define BIT22 0x00400000
+#define BIT23 0x00800000
+#define BIT24 0x01000000
+#define BIT25 0x02000000
+#define BIT26 0x04000000
+#define BIT27 0x08000000
+#define BIT28 0x10000000
+#define BIT29 0x20000000
+#define BIT30 0x40000000
+#define BIT31 0x80000000
+
diff --git a/src/wiring/comm/Serial.cpp b/src/wiring/comm/Serial.cpp new file mode 100644 index 0000000..3c43436 --- /dev/null +++ b/src/wiring/comm/Serial.cpp @@ -0,0 +1,67 @@ +//#include "stm32f10x_usart.h" +#include "stm32f10x_gpio.h" +#include "stm32f10x_rcc.h" +#include "gpio.h" +#include "Serial.h" +#include "wiring.h" + +int SendChar (int ch) { + /* Write character to Serial Port */ +// USART_SendData(USART2, (unsigned char) ch); +// while(USART_GetFlagStatus(USART2, USART_FLAG_TXE) == RESET) +// ; +// +// // while (!(USART2->SR & USART_FLAG_TXE)); +// return (ch); +} + +void uart_send(const char* str) { + while (*str != '\0') { + SendChar(*str); + str++; + } +} + + +Serial::Serial() { +} + +void Serial::write(uint8_t c) { + SendChar(c); +} + +void Serial::begin(uint32_t baud) { + // USART_InitTypeDef USART_InitStructure; + + /* Turn on the clock */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); + +#if 0 + /* Configure USART2 Tx as alternate function push-pull */ + GPIO_InitTypeDef GPIO_InitStructure; + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_Init(GPIOA, &GPIO_InitStructure); + + /* Configure USART2 Rx as input floating */ + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_Init(GPIOA, &GPIO_InitStructure); +#endif + + pinMode(1, GPIO_MODE_AF_OUTPUT_PP); + pinMode(0, GPIO_MODE_INPUT_FLOATING); + + /* Enable USART2 */ +// USART_InitStructure.USART_BaudRate = baud; +// USART_InitStructure.USART_WordLength = USART_WordLength_8b; +// USART_InitStructure.USART_StopBits = USART_StopBits_1; +// USART_InitStructure.USART_Parity = USART_Parity_No ; +// USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; +// USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; +// USART_Init(USART2, &USART_InitStructure); +// USART_Cmd(USART2, ENABLE); +} + +Serial Serial1; diff --git a/src/wiring/comm/Serial.h b/src/wiring/comm/Serial.h new file mode 100644 index 0000000..0e7a126 --- /dev/null +++ b/src/wiring/comm/Serial.h @@ -0,0 +1,20 @@ +#ifndef _SERIAL_H_ +#define _SERIAL_H_ + +#include <inttypes.h> +#include <Print.h> + +class Serial : public Print { + public: + Serial(); + void begin(uint32_t); + uint8_t available(void); + int read(void); + void flush(void); + virtual void write(uint8_t); + using Print::write; +}; + +extern Serial Serial1; +#endif + diff --git a/src/wiring/ext_interrupts.c b/src/wiring/ext_interrupts.c new file mode 100644 index 0000000..0a35472 --- /dev/null +++ b/src/wiring/ext_interrupts.c @@ -0,0 +1,65 @@ +#include "wiring.h" +#include "exti.h" +#include "ext_interrupts.h" + +typedef struct ExtiInfo { + uint8_t channel; + uint8_t port; +} ExtiInfo; + +static ExtiInfo PIN_TO_EXTI_CHANNEL[NR_MAPLE_PINS] = { + {EXTI3, EXTI_CONFIG_PORTA}, // D0/PA3 + {EXTI2, EXTI_CONFIG_PORTA}, // D1/PA2 + {EXTI0, EXTI_CONFIG_PORTA}, // D2/PA0 + {EXTI1, EXTI_CONFIG_PORTA}, // D3/PA1 + {EXTI5, EXTI_CONFIG_PORTB}, // D4/PB5 + {EXTI6, EXTI_CONFIG_PORTB}, // D5/PB6 + {EXTI8, EXTI_CONFIG_PORTA}, // D6/PA8 + {EXTI9, EXTI_CONFIG_PORTA}, // D7/PA9 + {EXTI10, EXTI_CONFIG_PORTA}, // D8/PA10 + {EXTI7, EXTI_CONFIG_PORTB}, // D9/PB7 + {EXTI4, EXTI_CONFIG_PORTA}, // D10/PA4 + {EXTI7, EXTI_CONFIG_PORTA}, // D11/PA7 + {EXTI6, EXTI_CONFIG_PORTA}, // D12/PA6 + {EXTI5, EXTI_CONFIG_PORTA}, // D13/PA5 +}; + + + +/** + * @brief Attach an interrupt handler to be triggered on a given + * transition on the pin. Runs in interrupt context + * + * @param[in] pin Maple pin number + * @param[in] handler Function to run upon external interrupt trigger. + * @param[in] mode Type of transition to trigger on, eg falling, rising, etc. + * + * @sideeffect Registers a handler + */ +int attachInterrupt(uint8_t pin, void (*handler)(void), uint8_t mode) { + /* Parameter checking */ + if (pin >= NR_MAPLE_PINS) { + return EXT_INTERRUPT_INVALID_PIN; + } + + if (!handler) { + return EXT_INTERRUPT_INVALID_FUNCTION; + } + + if (!(mode < NR_EXTI_MODES)) { + return EXT_INTERRUPT_INVALID_MODE; + } + + exti_attach_interrupt(PIN_TO_EXTI_CHANNEL[pin].channel, + PIN_TO_EXTI_CHANNEL[pin].port, + handler, mode); +} + +int detachInterrupt(uint8_t pin) { + if (!(pin < NR_MAPLE_PINS)) { + return EXT_INTERRUPT_INVALID_PIN; + } + + exti_detach_interrupt(PIN_TO_EXTI_CHANNEL[pin].channel); +} + diff --git a/src/wiring/ext_interrupts.h b/src/wiring/ext_interrupts.h new file mode 100644 index 0000000..d6fb23f --- /dev/null +++ b/src/wiring/ext_interrupts.h @@ -0,0 +1,31 @@ +#ifndef _EXT_INTERRUPTS_H_ +#define _EXT_INTERRUPTS_H_ + +#include "exti.h" + +#define RISING EXTI_RISING +#define FALLING EXTI_FALLING +#define CHANGE EXTI_RISING_FALLING + + +enum ExtInterruptError { + EXT_INTERRUPT_INVALID_PIN = (-1), + EXT_INTERRUPT_INVALID_FUNCTION = (-2), + EXT_INTERRUPT_INVALID_MODE = (-3), + +}; + +#ifdef __cplusplus +extern "C"{ +#endif + +int attachInterrupt(uint8_t, void ((*)(void)), uint8_t); +int detachInterrupt(uint8_t); + +#ifdef __cplusplus +} +#endif + + +#endif + diff --git a/src/wiring/io.h b/src/wiring/io.h new file mode 100644 index 0000000..387326a --- /dev/null +++ b/src/wiring/io.h @@ -0,0 +1,110 @@ +#ifndef _IO_H +#define _IO_H + +#include <inttypes.h> + +#ifdef __cplusplus +extern "C"{ +#endif + +/* stash these here for now */ +#define D0 0 +#define D1 1 +#define D2 2 +#define D3 3 +#define D4 4 +#define D5 5 +#define D6 6 +#define D7 7 +#define D8 8 +#define D9 9 +#define D10 10 +#define D11 11 +#define D12 12 +#define D13 13 +#define D14 14 +#define D15 15 +#define D16 16 +#define D16 16 +#define D17 17 +#define D18 18 +#define D19 19 +#define D20 20 +#define D21 21 +#define D22 22 +#define D23 23 +#define D24 24 +#define D25 25 +#define D26 26 +#define D27 27 +#define D28 28 +#define D29 29 +#define D30 30 +#define D31 31 +#define D32 32 +#define D33 33 +#define D34 34 +#define D35 35 +#define D36 36 +#define D37 37 +#define D38 38 +#define D39 39 + +#define A0 D14 +#define A1 D15 +#define A2 D16 +#define A3 D17 +#define A4 D18 +#define A5 D19 +#define A6 D0 +#define A7 D1 +#define A8 D2 +#define A9 D3 +#define A10 D10 +#define A11 D11 +#define A12 D12 +#define A13 D13 +#define A14 D26 +#define A15 D11 + +/* Set pin to mode + * pinMode(pin, mode): + * pin -> {0-38, D0-D39, A0-16} + * mode -> { + * INPUT/INPUT_DIGITAL + * INPUT_PULLUP + * INPUT_PULLDOWN + * INPUT_ANALOG + * OUTPUT/OUTPUT_PP + * OUTPUT_OPEN_DRAIN + * } + */ +void pinMode(uint8_t, uint8_t); + +/* + * Writes VALUE to digital pin[0-38] + * digitalWrite(pin, value): + * pin -> {0-38, D0-D39, A0-16} + * value -> LOW, HIGH; +*/ +void digitalWrite(uint8_t, uint8_t); + +/* Read a digital value from pin, the pin mode must be set to + * {INPUT, INPUT_PULLUP, INPUT_PULLDOWN} + * digitalRead(pin) + * pin -> {0-38, D0-D39, A0-16} + */ +uint32_t digitalRead(uint8_t); + +/* Read an analog value from pin, the pin mode must be set + * to INPUT_ANALOG + * analogRead(pin) + * pin -> {A0-A16} + * */ +uint32_t analogRead(uint8_t); + +#ifdef __cplusplus +} // extern "C" +#endif +#endif + diff --git a/src/wiring/math.cpp b/src/wiring/math.cpp new file mode 100644 index 0000000..9be7dc3 --- /dev/null +++ b/src/wiring/math.cpp @@ -0,0 +1,38 @@ +#include <stdlib.h> +#include "math.h" + +/* from newlib: + * + * rand returns the next pseudo-random integer in sequence; it is a number + * between 0 and RAND_MAX (inclusive). + * + * srand does not return a result. */ + + +/* The rest copied from WMath.cpp */ +void randomSeed(unsigned int seed) { + if (seed != 0) { + srand(seed); + } +} + +long random(long howbig) { + if (howbig == 0) { + return 0; + } + return rand() % howbig; +} + +long random(long howsmall, long howbig) { + if (howsmall >= howbig) { + return howsmall; + } + long diff = howbig - howsmall; + return random(diff) + howsmall; +} + +long map(long x, long in_min, long in_max, long out_min, long out_max) { + return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min; +} + + diff --git a/src/wiring/math.h b/src/wiring/math.h new file mode 100644 index 0000000..ee269e9 --- /dev/null +++ b/src/wiring/math.h @@ -0,0 +1,30 @@ +#ifndef _MAPLE_MATH_H_ +#define _MAPLE_MATH_H_ + +void randomSeed(unsigned int); +long random(long); +long random(long, long); +long map(long, long, long, long, long); + +#define PI 3.1415926535897932384626433832795 +#define HALF_PI 1.5707963267948966192313216916398 +#define TWO_PI 6.283185307179586476925286766559 +#define DEG_TO_RAD 0.017453292519943295769236907684886 +#define RAD_TO_DEG 57.295779513082320876798154814105 + +#define min(a,b) ((a)<(b)?(a):(b)) +#define max(a,b) ((a)>(b)?(a):(b)) +#define constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt))) +#define round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5)) +#define radians(deg) ((deg)*DEG_TO_RAD) +#define degrees(rad) ((rad)*RAD_TO_DEG) +#define sq(x) ((x)*(x)) + +/* undefine stdlib's abs if encountered */ +#ifdef abs +#undef abs +#endif +#define abs(x) (((x) > 0) ? (x) : -(unsigned)(x)) + +#endif + diff --git a/src/wiring/pwm.c b/src/wiring/pwm.c new file mode 100644 index 0000000..0c33c3a --- /dev/null +++ b/src/wiring/pwm.c @@ -0,0 +1,40 @@ +#include "wiring.h" +#include "timers.h" +#include "gpio.h" +#include "pwm.h" + +#define NOT_A_TIMER 0 + +static const TimerCCR PIN_TO_TIMER[NR_MAPLE_PINS] = { + TIMER2_CH4_CCR, // D0/A6 + TIMER2_CH3_CCR, // D1/A7 + TIMER2_CH1_CCR, // D2/A8 + TIMER2_CH2_CCR, // D3/A9 + NOT_A_TIMER, // D4 + TIMER4_CH1_CCR, // D5 + TIMER1_CH1_CCR, // D6 + TIMER1_CH2_CCR, // D7 + TIMER1_CH3_CCR, // D8 + TIMER4_CH2_CCR, // D9 + NOT_A_TIMER, // D10/A10 + TIMER3_CH2_CCR, // D11/A11 + TIMER3_CH1_CCR, // D12/A12 + NOT_A_TIMER, // D13/A13 +}; + +void pwmWrite(uint8_t pin, uint16_t duty_cycle) { + TimerCCR ccr; + + if (pin >= NR_MAPLE_PINS) { + return; + } + + ccr = PIN_TO_TIMER[pin]; + + if (ccr == NOT_A_TIMER) + return; + + timer_pwm_write_ccr(ccr, duty_cycle); +} + + diff --git a/src/wiring/pwm.h b/src/wiring/pwm.h new file mode 100644 index 0000000..3ff440b --- /dev/null +++ b/src/wiring/pwm.h @@ -0,0 +1,18 @@ +#ifndef _PWM_H +#define _PWM_H + +#ifdef __cplusplus +extern "C"{ +#endif + +#define PWM GPIO_MODE_AF_OUTPUT_PP + +void pwmWrite(uint8_t, uint16_t); + +#ifdef __cplusplus +} +#endif + + +#endif + diff --git a/src/wiring/time.c b/src/wiring/time.c new file mode 100644 index 0000000..bf6a28b --- /dev/null +++ b/src/wiring/time.c @@ -0,0 +1,59 @@ +#include "systick.h" +#include "time.h" + +#define CYCLES_PER_MICROSECOND 72 +#define THE_SECRET_TO_LIFE_THE_UNIVERSE_AND_EVERYTHING 42 + +extern volatile uint32_t systick_timer_millis; + +unsigned long millis() { + unsigned long m; + m = systick_timer_millis; + return m; +} + +void delay(unsigned long ms) +{ + unsigned long start = millis(); + + while (millis() - start <= ms) + ; +} + + +#define MAGIC 4096 +/* HZ = 1000 + * n HZ*/ +void delayMicroseconds(uint32_t us) { + uint32_t target; + uint32_t last, cur, count; + +#if 0 + asm volatile("mov r0, %[count] \n\t" +"1: \n\t" + "subs r0, r0, #1 \n\t" + "bne 1b" + : + : [count] "r" (count) + : "r0", "cc"); +#endif + +#if 1 + /* fudge factor hacky hack hack for function overhead */ + target = us * CYCLES_PER_MICROSECOND - THE_SECRET_TO_LIFE_THE_UNIVERSE_AND_EVERYTHING; + + /* Get current count */ + last = systick_get_count(); + cur = systick_get_count(); + count = last; + while ((count-cur) <= target) { + cur = systick_get_count(); + + /* check for overflow */ + if (cur > last) { + count += MAPLE_RELOAD_VAL; + } + last = cur; + } +#endif +} diff --git a/src/wiring/time.h b/src/wiring/time.h new file mode 100644 index 0000000..694545b --- /dev/null +++ b/src/wiring/time.h @@ -0,0 +1,27 @@ +#ifndef _TIME_H +#define _TIME_H + +#include <inttypes.h> + +#ifdef __cplusplus +extern "C"{ +#endif +/* Returns time since boot in milliseconds */ +uint32_t millis(void); + +/* Time in microseconds since boot */ +uint32_t micros(void); + +/* Delay for ms milliseconds */ +void delay(unsigned long ms); + +/* Delay for us microseconds */ +void delayMicroseconds(uint32_t us); + +#ifdef __cplusplus +} // extern "C" +#endif + + +#endif + diff --git a/src/wiring/wiring.c b/src/wiring/wiring.c new file mode 100644 index 0000000..83679c7 --- /dev/null +++ b/src/wiring/wiring.c @@ -0,0 +1,85 @@ +#include <inttypes.h> +#include "stm32f10x_flash.h" +#include "stm32f10x_rcc.h" +#include "stm32f10x_map.h" +#include "stm32f10x_nvic.h" +#include "wiring.h" +#include "systick.h" +#include "gpio.h" + +void RCC_Configuration(void); +void NVIC_Configuration(void); + +void init(void) { + RCC_Configuration(); + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | + RCC_APB2Periph_GPIOB | + RCC_APB2Periph_GPIOC | + RCC_APB2Periph_AFIO + , ENABLE); + NVIC_Configuration(); + + systick_init(); + + gpio_init(); + + /* off for debug */ +// adc_init(); + +// timer_init(1, 1); +// timer_init(2, 1); +// timer_init(3, 1); +// timer_init(4, 1); +} + +void NVIC_Configuration(void) { + /* Set the Vector Table base location at 0x08000000 */ + NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0); +} + + +void RCC_Configuration(void) { + ErrorStatus HSEStartUpStatus; + /* RCC system reset(for debug purpose) */ + RCC_DeInit(); + + /* Enable HSE */ + RCC_HSEConfig(RCC_HSE_ON); + + /* Wait till HSE is ready */ + HSEStartUpStatus = RCC_WaitForHSEStartUp(); + + if(HSEStartUpStatus == SUCCESS) { + /* Enable Prefetch Buffer */ + FLASH_PrefetchBufferCmd( (u32)FLASH_PrefetchBuffer_Enable); + + /* Flash 2 wait state */ + FLASH_SetLatency(FLASH_Latency_2); + + /* HCLK = SYSCLK */ + RCC_HCLKConfig(RCC_SYSCLK_Div1); + + /* PCLK2 = HCLK APB2 Periphs, no prescaler 72MHz */ + RCC_PCLK2Config(RCC_HCLK_Div1); + + /* PCLK1 = HCLK/2 APB1 periphs = 36MHZ*/ + RCC_PCLK1Config(RCC_HCLK_Div2); + + /* PLLCLK = 8MHz * 9 = 72 MHz */ + RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9); + + /* Enable PLL */ + RCC_PLLCmd(ENABLE); + + /* Wait till PLL is ready */ + while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET) + ; + + /* Select PLL as system clock source */ + RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK); + + /* Wait till PLL is used as system clock source */ + while(RCC_GetSYSCLKSource() != 0x08) + ; + } +} diff --git a/src/wiring/wiring.h b/src/wiring/wiring.h new file mode 100644 index 0000000..789e697 --- /dev/null +++ b/src/wiring/wiring.h @@ -0,0 +1,56 @@ +#ifndef _WIRING_H_ +#define _WIRING_H_ + +#include <inttypes.h> +#include "timers.h" +#include "io.h" +#include "binary.h" +#include "time.h" + +#ifdef __cplusplus +extern "C"{ +#endif + +#define MAPLE 1 +#define NR_MAPLE_PINS 14 // temporary + +#define HIGH 0x1 +#define LOW 0x0 + +#define true 0x1 +#define false 0x0 + +#define SERIAL 0x0 +#define DISPLAY 0x1 + +#define LSBFIRST 0 +#define MSBFIRST 1 + +#define lowByte(w) ((w) & 0xff) +#define highByte(w) ((w) >> 8) +#define bitRead(value, bit) (((value) >> (bit)) & 0x01) +#define bitSet(value, bit) ((value) |= (1UL << (bit))) +#define bitClear(value, bit) ((value) &= ~(1UL << (bit))) +#define bitWrite(value, bit, bitvalue) (bitvalue ? bitSet(value, bit) : bitClear(value, bit)) +#define bit(b) (1UL << (b)) + + +typedef uint8_t boolean; +typedef uint8_t byte; + +void init(void); + + +unsigned long pulseIn(uint8_t pin, uint8_t state, unsigned long timeout); +void shiftOut(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder, byte val); + + +#ifdef __cplusplus +} // extern "C" +#endif + + + + +#endif + diff --git a/src/wiring/wiring_analog.c b/src/wiring/wiring_analog.c new file mode 100644 index 0000000..abcf7c6 --- /dev/null +++ b/src/wiring/wiring_analog.c @@ -0,0 +1,33 @@ +#include "adc.h" +#include "gpio.h" +#include "wiring.h" +#include <stdio.h> + +/* Indexed by pins A[0-15] */ +uint32_t PIN_TO_ADC[NR_ANALOG_PINS] = { + 10, // A0/D14 ADC10 + 11, // A1/D15 ADC11 + 12, // A2/D16 ADC12 + 13, // A3/D17 ADC13 + 14, // A4/D18 ADC14 + 15, // A5/D19 ADC15 + 3, // A6/D0 ADC3 + 2, // A7/D1 ADC2 + 0, // A8/D2 ADC0 + 1, // A9/D3 ADC1 + 4, // A10/D10 ADC4 + 7, // A11/D11 ADC7 + 6, // A12/D12 ADC6 + 5, // A13/D13 ADC5 + 8, // A14/D26 ADC8 + 9, // A15/D11 ADC9 +}; + +/* Assumes that the ADC has been initialized and + * that the pin is set to ANALOG_INPUT */ +uint32_t analogRead(uint8_t pin) { + if (pin >= NR_ANALOG_PINS) + return 0; + + return adc_read(PIN_TO_ADC[pin]); +} diff --git a/src/wiring/wiring_digital.c b/src/wiring/wiring_digital.c new file mode 100644 index 0000000..1ece41a --- /dev/null +++ b/src/wiring/wiring_digital.c @@ -0,0 +1,55 @@ +#include "gpio.h" +#include "wiring.h" +#include "util.h" + +typedef struct PinGPIOMapping { + GPIO_Port *port; + uint32_t pin; +} PinGPIOMapping; + +static const PinGPIOMapping PIN_TO_GPIO[NR_MAPLE_PINS] = { + {_GPIOA_BASE, 3}, // D0/PA3 + {_GPIOA_BASE, 2}, // D1/PA2 + {_GPIOA_BASE, 0}, // D2/PA0 + {_GPIOA_BASE, 1}, // D3/PA1 + {_GPIOB_BASE, 5}, // D4/PB5 + {_GPIOB_BASE, 6}, // D5/PB6 + {_GPIOA_BASE, 8}, // D6/PA8 + {_GPIOA_BASE, 9}, // D7/PA9 + {_GPIOA_BASE, 10}, // D8/PA10 + {_GPIOB_BASE, 7}, // D9/PB7 + {_GPIOA_BASE, 4}, // D10/PA4 + {_GPIOA_BASE, 7}, // D11/PA7 + {_GPIOA_BASE, 6}, // D12/PA6 + {_GPIOA_BASE, 5}, // D13/PA5 +#if 0 + {_GPIOC_BASE, 0}, // D14/A0/PC0 + {_GPIOC_BASE, 1}, // D15/A1/PC1 + {_GPIOC_BASE, 2}, // D16/A2/PC2 + {_GPIOC_BASE, 3}, // D17/A3/PC3 + {_GPIOC_BASE, 4}, // D18/A4/PC4 + {_GPIOC_BASE, 5}, // D19/A5/PC5 +#endif +}; + +void pinMode(uint8_t pin, uint8_t mode) { + if (pin >= NR_MAPLE_PINS) + return; + + gpio_set_mode(PIN_TO_GPIO[pin].port, PIN_TO_GPIO[pin].pin, mode); +} + + +uint32_t digitalRead(uint8_t pin) { + if (pin >= NR_MAPLE_PINS) + return 0; + + return (PIN_TO_GPIO[pin].port->IDR & BIT(PIN_TO_GPIO[pin].pin)) ? 1 : 0; +} + +void digitalWrite(uint8_t pin, uint8_t val) { + if (pin >= NR_MAPLE_PINS) + return; + + gpio_write_bit(PIN_TO_GPIO[pin].port, PIN_TO_GPIO[pin].pin, val); +} diff --git a/src/wiring/wiring_shift.c b/src/wiring/wiring_shift.c new file mode 100644 index 0000000..c138b56 --- /dev/null +++ b/src/wiring/wiring_shift.c @@ -0,0 +1,42 @@ +/* copied straight from arduino/wiring_shift.c */ + +/* + wiring_shift.c - shiftOut() function + Part of Arduino - http://www.arduino.cc/ + + Copyright (c) 2005-2006 David A. Mellis + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General + Public License along with this library; if not, write to the + Free Software Foundation, Inc., 59 Temple Place, Suite 330, + Boston, MA 02111-1307 USA + + $Id: wiring.c 248 2007-02-03 15:36:30Z mellis $ +*/ + +#include "wiring.h" + +void shiftOut(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder, byte val) +{ + int i; + + for (i = 0; i < 8; i++) { + if (bitOrder == LSBFIRST) + digitalWrite(dataPin, !!(val & (1 << i))); + else + digitalWrite(dataPin, !!(val & (1 << (7 - i)))); + + digitalWrite(clockPin, HIGH); + digitalWrite(clockPin, LOW); + } +} diff --git a/stm32conf/flash.cfg b/stm32conf/flash.cfg new file mode 100644 index 0000000..86020bf --- /dev/null +++ b/stm32conf/flash.cfg @@ -0,0 +1,85 @@ +# script for stm32 + +interface ft2232 +ft2232_device_desc "Olimex OpenOCD JTAG" +ft2232_layout olimex-jtag +ft2232_vid_pid 0x15ba 0x0003 + +if { [info exists CHIPNAME] } { + set _CHIPNAME $CHIPNAME +} else { + set _CHIPNAME stm32 +} + +if { [info exists ENDIAN] } { + set _ENDIAN $ENDIAN +} else { + set _ENDIAN little +} + +# jtag speed speed should be <= F_CPU/6. F_CPU after reset is 8MHz, so ufse F_JTAG = 1MHz +jtag_khz 1000 + +jtag_nsrst_delay 100 +jtag_ntrst_delay 100 + +#use combined on interfaces or targets that can't set TRST/SRST separately +reset_config trst_and_srst + +#jtag scan chain +if { [info exists CPUTAPID ] } { + set _CPUTAPID $CPUTAPID +} else { + # See STM Document RM0008 + # Section 26.6.3 + set _CPUTAPID 0x3ba00477 +} + +jtag newtap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID + +if { [info exists BSTAPID ] } { + # FIXME this never gets used to override defaults... + set _BSTAPID $BSTAPID +} else { + # See STM Document RM0008 + # Section 29.6.2 + # Low density devices, Rev A + set _BSTAPID1 0x06412041 + # Medium density devices, Rev A + set _BSTAPID2 0x06410041 + # Medium density devices, Rev B and Rev Z + set _BSTAPID3 0x16410041 + # High density devices, Rev A + set _BSTAPID4 0x06414041 + # Connectivity line devices, Rev A and Rev Z + set _BSTAPID5 0x06418041 +} +jtag newtap $_CHIPNAME bs -irlen 5 -expected-id $_BSTAPID1 \ + -expected-id $_BSTAPID2 -expected-id $_BSTAPID3 \ + -expected-id $_BSTAPID4 -expected-id $_BSTAPID5 + + +set _TARGETNAME $_CHIPNAME.cpu +target create $_TARGETNAME cortex_m3 -endian $_ENDIAN -chain-position $_TARGETNAME + +$_TARGETNAME configure -work-area-virt 0 -work-area-phys 0x20000000 -work-area-size 0x5000 -work-area-backup 0 + +flash bank stm32x 0x08000000 0x00020000 0 0 $_TARGETNAME + +proc flash_chip {} { + echo "Halting..." + halt + echo "Erasing 128KB..." + flash erase_address 0x08000000 0x20000 + echo "Flashing image..." + flash write_bank 0 build/main.bin 0 + echo "Verifying image..." + verify_image build/main.bin 0x08000000 bin + echo "Checksum verified, resetting chip" + reset run + echo "Daemon shutdown" + shutdown +} + +init +flash_chip diff --git a/stm32conf/lanchon-stm32.ld b/stm32conf/lanchon-stm32.ld new file mode 100644 index 0000000..504f1d4 --- /dev/null +++ b/stm32conf/lanchon-stm32.ld @@ -0,0 +1,20 @@ +/* Linker script for STM32 (by Lanchon)
+ *
+ * Configure target memory and included script
+ * according to your application requirements. */
+
+/* Define memory spaces. */
+MEMORY
+{
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
+ rom (rx) : ORIGIN = 0x00000000, LENGTH = 128K
+}
+
+/* Include the appropriate script.
+ * Options:
+ * lanchon-stm32-rom.ld
+ * lanchon-stm32-rom-hosted.ld
+ * lanchon-stm32-ram.ld
+ * lanchon-stm32-ram-hosted.ld
+ */
+INCLUDE "lanchon-stm32-rom.ld"
diff --git a/stm32conf/lanchon-stm32/lanchon-stm32-128k-20k-rom.ld b/stm32conf/lanchon-stm32/lanchon-stm32-128k-20k-rom.ld new file mode 100644 index 0000000..133a8b5 --- /dev/null +++ b/stm32conf/lanchon-stm32/lanchon-stm32-128k-20k-rom.ld @@ -0,0 +1,20 @@ +/* Linker script for STM32 (by Lanchon)
+ *
+ * Configure target memory and included script
+ * according to your application requirements. */
+
+/* Define memory spaces. */
+MEMORY
+{
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
+ rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
+}
+
+/* Include the appropriate script.
+ * Options:
+ * lanchon-stm32-rom.ld
+ * lanchon-stm32-rom-hosted.ld
+ * lanchon-stm32-ram.ld
+ * lanchon-stm32-ram-hosted.ld
+ */
+INCLUDE "lanchon-stm32-rom.ld"
diff --git a/stm32conf/lanchon-stm32/lanchon-stm32-names.inc b/stm32conf/lanchon-stm32/lanchon-stm32-names.inc new file mode 100644 index 0000000..a0e1fb2 --- /dev/null +++ b/stm32conf/lanchon-stm32/lanchon-stm32-names.inc @@ -0,0 +1,61 @@ +/* ISR names for STM32 (by Lanchon) */
+
+EXTERN (__cs3_stack)
+EXTERN (__cs3_reset)
+EXTERN (NMIException)
+EXTERN (HardFaultException)
+EXTERN (MemManageException)
+EXTERN (BusFaultException)
+EXTERN (UsageFaultException)
+EXTERN (__STM32ReservedException7)
+EXTERN (__STM32ReservedException8)
+EXTERN (__STM32ReservedException9)
+EXTERN (__STM32ReservedException10)
+EXTERN (SVCHandler)
+EXTERN (DebugMonitor)
+EXTERN (__STM32ReservedException13)
+EXTERN (PendSVC)
+EXTERN (SysTickHandler)
+EXTERN (WWDG_IRQHandler)
+EXTERN (PVD_IRQHandler)
+EXTERN (TAMPER_IRQHandler)
+EXTERN (RTC_IRQHandler)
+EXTERN (FLASH_IRQHandler)
+EXTERN (RCC_IRQHandler)
+EXTERN (EXTI0_IRQHandler)
+EXTERN (EXTI1_IRQHandler)
+EXTERN (EXTI2_IRQHandler)
+EXTERN (EXTI3_IRQHandler)
+EXTERN (EXTI4_IRQHandler)
+EXTERN (DMAChannel1_IRQHandler)
+EXTERN (DMAChannel2_IRQHandler)
+EXTERN (DMAChannel3_IRQHandler)
+EXTERN (DMAChannel4_IRQHandler)
+EXTERN (DMAChannel5_IRQHandler)
+EXTERN (DMAChannel6_IRQHandler)
+EXTERN (DMAChannel7_IRQHandler)
+EXTERN (ADC_IRQHandler)
+EXTERN (USB_HP_CAN_TX_IRQHandler)
+EXTERN (USB_LP_CAN_RX0_IRQHandler)
+EXTERN (CAN_RX1_IRQHandler)
+EXTERN (CAN_SCE_IRQHandler)
+EXTERN (EXTI9_5_IRQHandler)
+EXTERN (TIM1_BRK_IRQHandler)
+EXTERN (TIM1_UP_IRQHandler)
+EXTERN (TIM1_TRG_COM_IRQHandler)
+EXTERN (TIM1_CC_IRQHandler)
+EXTERN (TIM2_IRQHandler)
+EXTERN (TIM3_IRQHandler)
+EXTERN (TIM4_IRQHandler)
+EXTERN (I2C1_EV_IRQHandler)
+EXTERN (I2C1_ER_IRQHandler)
+EXTERN (I2C2_EV_IRQHandler)
+EXTERN (I2C2_ER_IRQHandler)
+EXTERN (SPI1_IRQHandler)
+EXTERN (SPI2_IRQHandler)
+EXTERN (USART1_IRQHandler)
+EXTERN (USART2_IRQHandler)
+EXTERN (USART3_IRQHandler)
+EXTERN (EXTI15_10_IRQHandler)
+EXTERN (RTCAlarm_IRQHandler)
+EXTERN (USBWakeUp_IRQHandler)
diff --git a/stm32conf/lanchon-stm32/lanchon-stm32-ram-hosted.ld b/stm32conf/lanchon-stm32/lanchon-stm32-ram-hosted.ld new file mode 100644 index 0000000..3ab33ec --- /dev/null +++ b/stm32conf/lanchon-stm32/lanchon-stm32-ram-hosted.ld @@ -0,0 +1,203 @@ +/* Linker script for STM32 (by Lanchon)
+ *
+ * Version:Sourcery G++ 4.2-84
+ * BugURL:https://support.codesourcery.com/GNUToolchain/
+ *
+ * Copyright 2007 CodeSourcery.
+ *
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions. No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply. */
+
+OUTPUT_FORMAT ("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
+ENTRY(_start)
+SEARCH_DIR(.)
+/* GROUP(-lgcc -lc -lcs3 -lcs3hosted -lcs3-lanchon-stm32) */
+GROUP(libgcc.a libc.a libcs3.a libcs3hosted.a libcs3-lanchon-stm32.a)
+
+/* These force the linker to search for particular symbols from
+ * the start of the link process and thus ensure the user's
+ * overrides are picked up
+ */
+EXTERN(__cs3_reset_lanchon_stm32)
+INCLUDE lanchon-stm32-names.inc
+EXTERN(__cs3_interrupt_vector_lanchon_stm32)
+EXTERN(__cs3_start_c main __cs3_stack __cs3_heap_end)
+EXTERN(_start)
+/* force exit to be picked up in a hosted or os environment */
+EXTERN(exit atexit)
+
+PROVIDE(__cs3_stack = __cs3_region_start_ram + __cs3_region_size_ram);
+PROVIDE(__cs3_heap_start = _end);
+PROVIDE(__cs3_heap_end = __cs3_region_start_ram + __cs3_region_size_ram);
+
+SECTIONS
+{
+ .text :
+ {
+ CREATE_OBJECT_SYMBOLS
+ __cs3_region_start_ram = .;
+ *(.cs3.region-head.ram)
+ __cs3_interrupt_vector = __cs3_interrupt_vector_lanchon_stm32;
+ *(.cs3.interrupt_vector)
+ /* Make sure we pulled in an interrupt vector. */
+ ASSERT (. != __cs3_interrupt_vector_lanchon_stm32, "No interrupt vector");
+
+ PROVIDE(__cs3_reset_lanchon_stm32 = _start);
+ __cs3_reset = __cs3_reset_lanchon_stm32;
+ *(.cs3.reset)
+
+ *(.text .text.* .gnu.linkonce.t.*)
+ *(.plt)
+ *(.gnu.warning)
+ *(.glue_7t) *(.glue_7) *(.vfp11_veneer)
+
+ *(.rodata .rodata.* .gnu.linkonce.r.*)
+
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ *(.gcc_except_table)
+ *(.eh_frame_hdr)
+ *(.eh_frame)
+
+ . = ALIGN(4);
+ KEEP(*(.init))
+
+ . = ALIGN(4);
+ __preinit_array_start = .;
+ KEEP (*(.preinit_array))
+ __preinit_array_end = .;
+
+ . = ALIGN(4);
+ __init_array_start = .;
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array))
+ __init_array_end = .;
+
+ . = ALIGN(0x4);
+ KEEP (*crtbegin.o(.ctors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
+ KEEP (*(SORT(.ctors.*)))
+ KEEP (*crtend.o(.ctors))
+
+ . = ALIGN(4);
+ KEEP(*(.fini))
+
+ . = ALIGN(4);
+ __fini_array_start = .;
+ KEEP (*(.fini_array))
+ KEEP (*(SORT(.fini_array.*)))
+ __fini_array_end = .;
+
+ KEEP (*crtbegin.o(.dtors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
+ KEEP (*(SORT(.dtors.*)))
+ KEEP (*crtend.o(.dtors))
+
+ . = ALIGN(4);
+ __cs3_regions = .;
+ LONG (0)
+ LONG (__cs3_region_init_ram)
+ LONG (__cs3_region_start_ram)
+ LONG (__cs3_region_init_size_ram)
+ LONG (__cs3_region_zero_size_ram)
+ } >ram
+
+ /* .ARM.exidx is sorted, so has to go in its own output section. */
+ __exidx_start = .;
+ .ARM.exidx :
+ {
+ *(.ARM.exidx* .gnu.linkonce.armexidx.*)
+ } >ram
+ __exidx_end = .;
+ .text.align :
+ {
+ . = ALIGN(8);
+ _etext = .;
+ } >ram
+
+ .cs3.rom :
+ {
+ __cs3_region_start_rom = .;
+ *(.cs3.region-head.rom)
+ *(.rom)
+ . = ALIGN (8);
+ } >rom
+ .cs3.rom.bss :
+ {
+ *(.rom.b)
+ . = ALIGN (8);
+ } >rom
+ /* __cs3_region_end_rom is deprecated */
+ __cs3_region_end_rom = __cs3_region_start_rom + LENGTH(rom);
+ __cs3_region_size_rom = LENGTH(rom);
+ __cs3_region_init_rom = LOADADDR (.cs3.rom);
+ __cs3_region_init_size_rom = SIZEOF(.cs3.rom);
+ __cs3_region_zero_size_rom = SIZEOF(.cs3.rom.bss);
+
+ .data :
+ {
+
+ KEEP(*(.jcr))
+ *(.got.plt) *(.got)
+ *(.shdata)
+ *(.data .data.* .gnu.linkonce.d.*)
+ *(.ram)
+ . = ALIGN (8);
+ _edata = .;
+ } >ram
+ .bss :
+ {
+ *(.shbss)
+ *(.bss .bss.* .gnu.linkonce.b.*)
+ *(COMMON)
+ *(.ram.b)
+ . = ALIGN (8);
+ _end = .;
+ __end = .;
+ } >ram
+ /* __cs3_region_end_ram is deprecated */
+ __cs3_region_end_ram = __cs3_region_start_ram + LENGTH(ram);
+ __cs3_region_size_ram = LENGTH(ram);
+ __cs3_region_init_ram = LOADADDR (.text);
+ __cs3_region_init_size_ram = _edata - ADDR (.text);
+ __cs3_region_zero_size_ram = _end - _edata;
+ __cs3_region_num = 1;
+
+ .stab 0 (NOLOAD) : { *(.stab) }
+ .stabstr 0 (NOLOAD) : { *(.stabstr) }
+ /* DWARF debug sections.
+ * Symbols in the DWARF debugging sections are relative to the beginning
+ * of the section so we begin them at 0. */
+ /* DWARF 1 */
+ .debug 0 : { *(.debug) }
+ .line 0 : { *(.line) }
+ /* GNU DWARF 1 extensions */
+ .debug_srcinfo 0 : { *(.debug_srcinfo) }
+ .debug_sfnames 0 : { *(.debug_sfnames) }
+ /* DWARF 1.1 and DWARF 2 */
+ .debug_aranges 0 : { *(.debug_aranges) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ /* DWARF 2 */
+ .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_frame 0 : { *(.debug_frame) }
+ .debug_str 0 : { *(.debug_str) }
+ .debug_loc 0 : { *(.debug_loc) }
+ .debug_macinfo 0 : { *(.debug_macinfo) }
+ /* SGI/MIPS DWARF 2 extensions */
+ .debug_weaknames 0 : { *(.debug_weaknames) }
+ .debug_funcnames 0 : { *(.debug_funcnames) }
+ .debug_typenames 0 : { *(.debug_typenames) }
+ .debug_varnames 0 : { *(.debug_varnames) }
+
+ .note.gnu.arm.ident 0 : { KEEP (*(.note.gnu.arm.ident)) }
+ .ARM.attributes 0 : { KEEP (*(.ARM.attributes)) }
+ /DISCARD/ : { *(.note.GNU-stack) }
+}
diff --git a/stm32conf/lanchon-stm32/lanchon-stm32-ram.ld b/stm32conf/lanchon-stm32/lanchon-stm32-ram.ld new file mode 100644 index 0000000..59c321e --- /dev/null +++ b/stm32conf/lanchon-stm32/lanchon-stm32-ram.ld @@ -0,0 +1,201 @@ +/* Linker script for STM32 (by Lanchon)
+ *
+ * Version:Sourcery G++ 4.2-84
+ * BugURL:https://support.codesourcery.com/GNUToolchain/
+ *
+ * Copyright 2007 CodeSourcery.
+ *
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions. No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply. */
+
+OUTPUT_FORMAT ("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
+ENTRY(_start)
+SEARCH_DIR(.)
+/* GROUP(-lgcc -lc -lcs3 -lcs3unhosted -lcs3-lanchon-stm32) */
+GROUP(libgcc.a libc.a libcs3.a libcs3unhosted.a libcs3-lanchon-stm32.a)
+
+/* These force the linker to search for particular symbols from
+ * the start of the link process and thus ensure the user's
+ * overrides are picked up
+ */
+EXTERN(__cs3_reset_lanchon_stm32)
+INCLUDE lanchon-stm32-names.inc
+EXTERN(__cs3_interrupt_vector_lanchon_stm32)
+EXTERN(__cs3_start_c main __cs3_stack __cs3_heap_end)
+EXTERN(_start)
+
+PROVIDE(__cs3_stack = __cs3_region_start_ram + __cs3_region_size_ram);
+PROVIDE(__cs3_heap_start = _end);
+PROVIDE(__cs3_heap_end = __cs3_region_start_ram + __cs3_region_size_ram);
+
+SECTIONS
+{
+ .text :
+ {
+ CREATE_OBJECT_SYMBOLS
+ __cs3_region_start_ram = .;
+ *(.cs3.region-head.ram)
+ __cs3_interrupt_vector = __cs3_interrupt_vector_lanchon_stm32;
+ *(.cs3.interrupt_vector)
+ /* Make sure we pulled in an interrupt vector. */
+ ASSERT (. != __cs3_interrupt_vector_lanchon_stm32, "No interrupt vector");
+
+ PROVIDE(__cs3_reset_lanchon_stm32 = _start);
+ __cs3_reset = __cs3_reset_lanchon_stm32;
+ *(.cs3.reset)
+
+ *(.text .text.* .gnu.linkonce.t.*)
+ *(.plt)
+ *(.gnu.warning)
+ *(.glue_7t) *(.glue_7) *(.vfp11_veneer)
+
+ *(.rodata .rodata.* .gnu.linkonce.r.*)
+
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ *(.gcc_except_table)
+ *(.eh_frame_hdr)
+ *(.eh_frame)
+
+ . = ALIGN(4);
+ KEEP(*(.init))
+
+ . = ALIGN(4);
+ __preinit_array_start = .;
+ KEEP (*(.preinit_array))
+ __preinit_array_end = .;
+
+ . = ALIGN(4);
+ __init_array_start = .;
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array))
+ __init_array_end = .;
+
+ . = ALIGN(0x4);
+ KEEP (*crtbegin.o(.ctors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
+ KEEP (*(SORT(.ctors.*)))
+ KEEP (*crtend.o(.ctors))
+
+ . = ALIGN(4);
+ KEEP(*(.fini))
+
+ . = ALIGN(4);
+ __fini_array_start = .;
+ KEEP (*(.fini_array))
+ KEEP (*(SORT(.fini_array.*)))
+ __fini_array_end = .;
+
+ KEEP (*crtbegin.o(.dtors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
+ KEEP (*(SORT(.dtors.*)))
+ KEEP (*crtend.o(.dtors))
+
+ . = ALIGN(4);
+ __cs3_regions = .;
+ LONG (0)
+ LONG (__cs3_region_init_ram)
+ LONG (__cs3_region_start_ram)
+ LONG (__cs3_region_init_size_ram)
+ LONG (__cs3_region_zero_size_ram)
+ } >ram
+
+ /* .ARM.exidx is sorted, so has to go in its own output section. */
+ __exidx_start = .;
+ .ARM.exidx :
+ {
+ *(.ARM.exidx* .gnu.linkonce.armexidx.*)
+ } >ram
+ __exidx_end = .;
+ .text.align :
+ {
+ . = ALIGN(8);
+ _etext = .;
+ } >ram
+
+ .cs3.rom :
+ {
+ __cs3_region_start_rom = .;
+ *(.cs3.region-head.rom)
+ *(.rom)
+ . = ALIGN (8);
+ } >rom
+ .cs3.rom.bss :
+ {
+ *(.rom.b)
+ . = ALIGN (8);
+ } >rom
+ /* __cs3_region_end_rom is deprecated */
+ __cs3_region_end_rom = __cs3_region_start_rom + LENGTH(rom);
+ __cs3_region_size_rom = LENGTH(rom);
+ __cs3_region_init_rom = LOADADDR (.cs3.rom);
+ __cs3_region_init_size_rom = SIZEOF(.cs3.rom);
+ __cs3_region_zero_size_rom = SIZEOF(.cs3.rom.bss);
+
+ .data :
+ {
+
+ KEEP(*(.jcr))
+ *(.got.plt) *(.got)
+ *(.shdata)
+ *(.data .data.* .gnu.linkonce.d.*)
+ *(.ram)
+ . = ALIGN (8);
+ _edata = .;
+ } >ram
+ .bss :
+ {
+ *(.shbss)
+ *(.bss .bss.* .gnu.linkonce.b.*)
+ *(COMMON)
+ *(.ram.b)
+ . = ALIGN (8);
+ _end = .;
+ __end = .;
+ } >ram
+ /* __cs3_region_end_ram is deprecated */
+ __cs3_region_end_ram = __cs3_region_start_ram + LENGTH(ram);
+ __cs3_region_size_ram = LENGTH(ram);
+ __cs3_region_init_ram = LOADADDR (.text);
+ __cs3_region_init_size_ram = _edata - ADDR (.text);
+ __cs3_region_zero_size_ram = _end - _edata;
+ __cs3_region_num = 1;
+
+ .stab 0 (NOLOAD) : { *(.stab) }
+ .stabstr 0 (NOLOAD) : { *(.stabstr) }
+ /* DWARF debug sections.
+ * Symbols in the DWARF debugging sections are relative to the beginning
+ * of the section so we begin them at 0. */
+ /* DWARF 1 */
+ .debug 0 : { *(.debug) }
+ .line 0 : { *(.line) }
+ /* GNU DWARF 1 extensions */
+ .debug_srcinfo 0 : { *(.debug_srcinfo) }
+ .debug_sfnames 0 : { *(.debug_sfnames) }
+ /* DWARF 1.1 and DWARF 2 */
+ .debug_aranges 0 : { *(.debug_aranges) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ /* DWARF 2 */
+ .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_frame 0 : { *(.debug_frame) }
+ .debug_str 0 : { *(.debug_str) }
+ .debug_loc 0 : { *(.debug_loc) }
+ .debug_macinfo 0 : { *(.debug_macinfo) }
+ /* SGI/MIPS DWARF 2 extensions */
+ .debug_weaknames 0 : { *(.debug_weaknames) }
+ .debug_funcnames 0 : { *(.debug_funcnames) }
+ .debug_typenames 0 : { *(.debug_typenames) }
+ .debug_varnames 0 : { *(.debug_varnames) }
+
+ .note.gnu.arm.ident 0 : { KEEP (*(.note.gnu.arm.ident)) }
+ .ARM.attributes 0 : { KEEP (*(.ARM.attributes)) }
+ /DISCARD/ : { *(.note.GNU-stack) }
+}
diff --git a/stm32conf/lanchon-stm32/lanchon-stm32-rom-hosted.ld b/stm32conf/lanchon-stm32/lanchon-stm32-rom-hosted.ld new file mode 100644 index 0000000..d7de11a --- /dev/null +++ b/stm32conf/lanchon-stm32/lanchon-stm32-rom-hosted.ld @@ -0,0 +1,191 @@ +/* Linker script for STM32 (by Lanchon)
+ *
+ * Version:Sourcery G++ 4.2-84
+ * BugURL:https://support.codesourcery.com/GNUToolchain/
+ *
+ * Copyright 2007 CodeSourcery.
+ *
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions. No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply. */
+
+OUTPUT_FORMAT ("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
+ENTRY(_start)
+SEARCH_DIR(.)
+/* GROUP(-lgcc -lc -lcs3 -lcs3hosted -lcs3-lanchon-stm32) */
+GROUP(libgcc.a libc.a libcs3.a libcs3hosted.a libcs3-lanchon-stm32.a)
+
+/* These force the linker to search for particular symbols from
+ * the start of the link process and thus ensure the user's
+ * overrides are picked up
+ */
+EXTERN(__cs3_reset_lanchon_stm32)
+INCLUDE lanchon-stm32-names.inc
+EXTERN(__cs3_interrupt_vector_lanchon_stm32)
+EXTERN(__cs3_start_c main __cs3_stack __cs3_heap_end)
+EXTERN(_start)
+/* force exit to be picked up in a hosted or os environment */
+EXTERN(exit atexit)
+
+PROVIDE(__cs3_stack = __cs3_region_start_ram + __cs3_region_size_ram);
+PROVIDE(__cs3_heap_start = _end);
+PROVIDE(__cs3_heap_end = __cs3_region_start_ram + __cs3_region_size_ram);
+
+SECTIONS
+{
+ .text :
+ {
+ CREATE_OBJECT_SYMBOLS
+ __cs3_region_start_rom = .;
+ *(.cs3.region-head.rom)
+ __cs3_interrupt_vector = __cs3_interrupt_vector_lanchon_stm32;
+ *(.cs3.interrupt_vector)
+ /* Make sure we pulled in an interrupt vector. */
+ ASSERT (. != __cs3_interrupt_vector_lanchon_stm32, "No interrupt vector");
+ *(.rom)
+ *(.rom.b)
+
+ PROVIDE(__cs3_reset_lanchon_stm32 = _start);
+ __cs3_reset = __cs3_reset_lanchon_stm32;
+ *(.cs3.reset)
+
+ *(.text .text.* .gnu.linkonce.t.*)
+ *(.plt)
+ *(.gnu.warning)
+ *(.glue_7t) *(.glue_7) *(.vfp11_veneer)
+
+ *(.rodata .rodata.* .gnu.linkonce.r.*)
+
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ *(.gcc_except_table)
+ *(.eh_frame_hdr)
+ *(.eh_frame)
+
+ . = ALIGN(4);
+ KEEP(*(.init))
+
+ . = ALIGN(4);
+ __preinit_array_start = .;
+ KEEP (*(.preinit_array))
+ __preinit_array_end = .;
+
+ . = ALIGN(4);
+ __init_array_start = .;
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array))
+ __init_array_end = .;
+
+ . = ALIGN(0x4);
+ KEEP (*crtbegin.o(.ctors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
+ KEEP (*(SORT(.ctors.*)))
+ KEEP (*crtend.o(.ctors))
+
+ . = ALIGN(4);
+ KEEP(*(.fini))
+
+ . = ALIGN(4);
+ __fini_array_start = .;
+ KEEP (*(.fini_array))
+ KEEP (*(SORT(.fini_array.*)))
+ __fini_array_end = .;
+
+ KEEP (*crtbegin.o(.dtors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
+ KEEP (*(SORT(.dtors.*)))
+ KEEP (*crtend.o(.dtors))
+
+ . = ALIGN(4);
+ __cs3_regions = .;
+ LONG (0)
+ LONG (__cs3_region_init_ram)
+ LONG (__cs3_region_start_ram)
+ LONG (__cs3_region_init_size_ram)
+ LONG (__cs3_region_zero_size_ram)
+ } >rom
+
+ /* .ARM.exidx is sorted, so has to go in its own output section. */
+ __exidx_start = .;
+ .ARM.exidx :
+ {
+ *(.ARM.exidx* .gnu.linkonce.armexidx.*)
+ } >rom
+ __exidx_end = .;
+ .text.align :
+ {
+ . = ALIGN(8);
+ _etext = .;
+ } >rom
+ /* __cs3_region_end_rom is deprecated */
+ __cs3_region_end_rom = __cs3_region_start_rom + LENGTH(rom);
+ __cs3_region_size_rom = LENGTH(rom);
+ __cs3_region_num = 1;
+
+ .data :
+ {
+ __cs3_region_start_ram = .;
+ *(.cs3.region-head.ram)
+ KEEP(*(.jcr))
+ *(.got.plt) *(.got)
+ *(.shdata)
+ *(.data .data.* .gnu.linkonce.d.*)
+ *(.ram)
+ . = ALIGN (8);
+ _edata = .;
+ } >ram AT>rom
+ .bss :
+ {
+ *(.shbss)
+ *(.bss .bss.* .gnu.linkonce.b.*)
+ *(COMMON)
+ *(.ram.b)
+ . = ALIGN (8);
+ _end = .;
+ __end = .;
+ } >ram AT>rom
+ /* __cs3_region_end_ram is deprecated */
+ __cs3_region_end_ram = __cs3_region_start_ram + LENGTH(ram);
+ __cs3_region_size_ram = LENGTH(ram);
+ __cs3_region_init_ram = LOADADDR (.data);
+ __cs3_region_init_size_ram = _edata - ADDR (.data);
+ __cs3_region_zero_size_ram = _end - _edata;
+ __cs3_region_num = 1;
+
+ .stab 0 (NOLOAD) : { *(.stab) }
+ .stabstr 0 (NOLOAD) : { *(.stabstr) }
+ /* DWARF debug sections.
+ * Symbols in the DWARF debugging sections are relative to the beginning
+ * of the section so we begin them at 0. */
+ /* DWARF 1 */
+ .debug 0 : { *(.debug) }
+ .line 0 : { *(.line) }
+ /* GNU DWARF 1 extensions */
+ .debug_srcinfo 0 : { *(.debug_srcinfo) }
+ .debug_sfnames 0 : { *(.debug_sfnames) }
+ /* DWARF 1.1 and DWARF 2 */
+ .debug_aranges 0 : { *(.debug_aranges) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ /* DWARF 2 */
+ .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_frame 0 : { *(.debug_frame) }
+ .debug_str 0 : { *(.debug_str) }
+ .debug_loc 0 : { *(.debug_loc) }
+ .debug_macinfo 0 : { *(.debug_macinfo) }
+ /* SGI/MIPS DWARF 2 extensions */
+ .debug_weaknames 0 : { *(.debug_weaknames) }
+ .debug_funcnames 0 : { *(.debug_funcnames) }
+ .debug_typenames 0 : { *(.debug_typenames) }
+ .debug_varnames 0 : { *(.debug_varnames) }
+
+ .note.gnu.arm.ident 0 : { KEEP (*(.note.gnu.arm.ident)) }
+ .ARM.attributes 0 : { KEEP (*(.ARM.attributes)) }
+ /DISCARD/ : { *(.note.GNU-stack) }
+}
diff --git a/stm32conf/lanchon-stm32/lanchon-stm32-rom.ld b/stm32conf/lanchon-stm32/lanchon-stm32-rom.ld new file mode 100644 index 0000000..909557f --- /dev/null +++ b/stm32conf/lanchon-stm32/lanchon-stm32-rom.ld @@ -0,0 +1,189 @@ +/* Linker script for STM32 (by Lanchon)
+ *
+ * Version:Sourcery G++ 4.2-84
+ * BugURL:https://support.codesourcery.com/GNUToolchain/
+ *
+ * Copyright 2007 CodeSourcery.
+ *
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions. No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply. */
+
+OUTPUT_FORMAT ("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
+ENTRY(_start)
+SEARCH_DIR(.)
+/* GROUP(-lgcc -lc -lcs3 -lcs3unhosted -lcs3-lanchon-stm32) */
+GROUP(libgcc.a libc.a libcs3.a libcs3unhosted.a libcs3-lanchon-stm32.a)
+
+/* These force the linker to search for particular symbols from
+ * the start of the link process and thus ensure the user's
+ * overrides are picked up
+ */
+EXTERN(__cs3_reset_lanchon_stm32)
+INCLUDE lanchon-stm32-names.inc
+EXTERN(__cs3_interrupt_vector_lanchon_stm32)
+EXTERN(__cs3_start_c main __cs3_stack __cs3_heap_end)
+EXTERN(_start)
+
+PROVIDE(__cs3_stack = __cs3_region_start_ram + __cs3_region_size_ram);
+PROVIDE(__cs3_heap_start = _end);
+PROVIDE(__cs3_heap_end = __cs3_region_start_ram + __cs3_region_size_ram);
+
+SECTIONS
+{
+ .text :
+ {
+ CREATE_OBJECT_SYMBOLS
+ __cs3_region_start_rom = .;
+ *(.cs3.region-head.rom)
+ __cs3_interrupt_vector = __cs3_interrupt_vector_lanchon_stm32;
+ *(.cs3.interrupt_vector)
+ /* Make sure we pulled in an interrupt vector. */
+ ASSERT (. != __cs3_interrupt_vector_lanchon_stm32, "No interrupt vector");
+ *(.rom)
+ *(.rom.b)
+
+ PROVIDE(__cs3_reset_lanchon_stm32 = _start);
+ __cs3_reset = __cs3_reset_lanchon_stm32;
+ *(.cs3.reset)
+
+ *(.text .text.* .gnu.linkonce.t.*)
+ *(.plt)
+ *(.gnu.warning)
+ *(.glue_7t) *(.glue_7) *(.vfp11_veneer)
+
+ *(.rodata .rodata.* .gnu.linkonce.r.*)
+
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ *(.gcc_except_table)
+ *(.eh_frame_hdr)
+ *(.eh_frame)
+
+ . = ALIGN(4);
+ KEEP(*(.init))
+
+ . = ALIGN(4);
+ __preinit_array_start = .;
+ KEEP (*(.preinit_array))
+ __preinit_array_end = .;
+
+ . = ALIGN(4);
+ __init_array_start = .;
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array))
+ __init_array_end = .;
+
+ . = ALIGN(0x4);
+ KEEP (*crtbegin.o(.ctors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
+ KEEP (*(SORT(.ctors.*)))
+ KEEP (*crtend.o(.ctors))
+
+ . = ALIGN(4);
+ KEEP(*(.fini))
+
+ . = ALIGN(4);
+ __fini_array_start = .;
+ KEEP (*(.fini_array))
+ KEEP (*(SORT(.fini_array.*)))
+ __fini_array_end = .;
+
+ KEEP (*crtbegin.o(.dtors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
+ KEEP (*(SORT(.dtors.*)))
+ KEEP (*crtend.o(.dtors))
+
+ . = ALIGN(4);
+ __cs3_regions = .;
+ LONG (0)
+ LONG (__cs3_region_init_ram)
+ LONG (__cs3_region_start_ram)
+ LONG (__cs3_region_init_size_ram)
+ LONG (__cs3_region_zero_size_ram)
+ } >rom
+
+ /* .ARM.exidx is sorted, so has to go in its own output section. */
+ __exidx_start = .;
+ .ARM.exidx :
+ {
+ *(.ARM.exidx* .gnu.linkonce.armexidx.*)
+ } >rom
+ __exidx_end = .;
+ .text.align :
+ {
+ . = ALIGN(8);
+ _etext = .;
+ } >rom
+ /* __cs3_region_end_rom is deprecated */
+ __cs3_region_end_rom = __cs3_region_start_rom + LENGTH(rom);
+ __cs3_region_size_rom = LENGTH(rom);
+ __cs3_region_num = 1;
+
+ .data :
+ {
+ __cs3_region_start_ram = .;
+ *(.cs3.region-head.ram)
+ KEEP(*(.jcr))
+ *(.got.plt) *(.got)
+ *(.shdata)
+ *(.data .data.* .gnu.linkonce.d.*)
+ *(.ram)
+ . = ALIGN (8);
+ _edata = .;
+ } >ram AT>rom
+ .bss :
+ {
+ *(.shbss)
+ *(.bss .bss.* .gnu.linkonce.b.*)
+ *(COMMON)
+ *(.ram.b)
+ . = ALIGN (8);
+ _end = .;
+ __end = .;
+ } >ram AT>rom
+ /* __cs3_region_end_ram is deprecated */
+ __cs3_region_end_ram = __cs3_region_start_ram + LENGTH(ram);
+ __cs3_region_size_ram = LENGTH(ram);
+ __cs3_region_init_ram = LOADADDR (.data);
+ __cs3_region_init_size_ram = _edata - ADDR (.data);
+ __cs3_region_zero_size_ram = _end - _edata;
+ __cs3_region_num = 1;
+
+ .stab 0 (NOLOAD) : { *(.stab) }
+ .stabstr 0 (NOLOAD) : { *(.stabstr) }
+ /* DWARF debug sections.
+ * Symbols in the DWARF debugging sections are relative to the beginning
+ * of the section so we begin them at 0. */
+ /* DWARF 1 */
+ .debug 0 : { *(.debug) }
+ .line 0 : { *(.line) }
+ /* GNU DWARF 1 extensions */
+ .debug_srcinfo 0 : { *(.debug_srcinfo) }
+ .debug_sfnames 0 : { *(.debug_sfnames) }
+ /* DWARF 1.1 and DWARF 2 */
+ .debug_aranges 0 : { *(.debug_aranges) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ /* DWARF 2 */
+ .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_frame 0 : { *(.debug_frame) }
+ .debug_str 0 : { *(.debug_str) }
+ .debug_loc 0 : { *(.debug_loc) }
+ .debug_macinfo 0 : { *(.debug_macinfo) }
+ /* SGI/MIPS DWARF 2 extensions */
+ .debug_weaknames 0 : { *(.debug_weaknames) }
+ .debug_funcnames 0 : { *(.debug_funcnames) }
+ .debug_typenames 0 : { *(.debug_typenames) }
+ .debug_varnames 0 : { *(.debug_varnames) }
+
+ .note.gnu.arm.ident 0 : { KEEP (*(.note.gnu.arm.ident)) }
+ .ARM.attributes 0 : { KEEP (*(.ARM.attributes)) }
+ /DISCARD/ : { *(.note.GNU-stack) }
+}
diff --git a/stm32conf/lanchon-stm32/src.zip b/stm32conf/lanchon-stm32/src.zip Binary files differnew file mode 100644 index 0000000..58ff908 --- /dev/null +++ b/stm32conf/lanchon-stm32/src.zip diff --git a/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-isrs.S.epilog b/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-isrs.S.epilog new file mode 100644 index 0000000..7102d59 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-isrs.S.epilog @@ -0,0 +1,2 @@ +
+#endif /* L_lanchon_stm32_isr_interrupt */
diff --git a/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-isrs.S.prolog b/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-isrs.S.prolog new file mode 100644 index 0000000..8e0629b --- /dev/null +++ b/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-isrs.S.prolog @@ -0,0 +1,14 @@ +/* ISRs for STM32 (by Lanchon) */
+
+ .thumb
+
+#if defined (L_lanchon_stm32_isr_interrupt)
+
+ .globl __STM32DefaultExceptionHandler
+ .type __STM32DefaultExceptionHandler, %function
+
+__STM32DefaultExceptionHandler:
+ b .
+
+ .size __STM32DefaultExceptionHandler, . - __STM32DefaultExceptionHandler
+
diff --git a/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-names.inc.epilog b/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-names.inc.epilog new file mode 100644 index 0000000..e69de29 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-names.inc.epilog diff --git a/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-names.inc.prolog b/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-names.inc.prolog new file mode 100644 index 0000000..a233a3f --- /dev/null +++ b/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-names.inc.prolog @@ -0,0 +1,4 @@ +/* ISR names for STM32 (by Lanchon) */
+
+EXTERN (__cs3_stack)
+EXTERN (__cs3_reset)
diff --git a/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-vector.S.epilog b/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-vector.S.epilog new file mode 100644 index 0000000..c8f3f4b --- /dev/null +++ b/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-vector.S.epilog @@ -0,0 +1,2 @@ +
+ .size __cs3_interrupt_vector_lanchon_stm32, . - __cs3_interrupt_vector_lanchon_stm32
diff --git a/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-vector.S.prolog b/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-vector.S.prolog new file mode 100644 index 0000000..85fa6f5 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/exceptions/lanchon-stm32-vector.S.prolog @@ -0,0 +1,10 @@ +/* Vector table for STM32 (by Lanchon) */
+
+ .section ".cs3.interrupt_vector"
+
+ .globl __cs3_interrupt_vector_lanchon_stm32
+ .type __cs3_interrupt_vector_lanchon_stm32, %object
+
+__cs3_interrupt_vector_lanchon_stm32:
+ .long __cs3_stack
+ .long __cs3_reset
diff --git a/stm32conf/lanchon-stm32/src/exceptions/make-clean.cmd b/stm32conf/lanchon-stm32/src/exceptions/make-clean.cmd new file mode 100644 index 0000000..82e4746 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/exceptions/make-clean.cmd @@ -0,0 +1,10 @@ +@echo off
+setlocal
+
+set DO=del
+
+%DO% lanchon-stm32-vector.S
+%DO% lanchon-stm32-isrs.S
+%DO% lanchon-stm32-names.inc
+%DO% stm32exceptions.h
+%DO% stm32exceptions.c
diff --git a/stm32conf/lanchon-stm32/src/exceptions/make-foreach.cmd b/stm32conf/lanchon-stm32/src/exceptions/make-foreach.cmd new file mode 100644 index 0000000..4c3b00e --- /dev/null +++ b/stm32conf/lanchon-stm32/src/exceptions/make-foreach.cmd @@ -0,0 +1,38 @@ +setlocal
+
+set ADR=0x%~1
+set TYPE=%~2
+set NAME=%~3
+set TEXT=%~4
+set HELP=%~5
+
+set /a NUM=%ADR%/4
+if %TYPE%==x set NAME=__STM32ReservedException%NUM%
+if %TYPE%==e set FULLTYPE=Exception
+if %TYPE%==i set FULLTYPE=Interrupt
+set FULLTEXT=%TEXT% %FULLTYPE%
+if not "%HELP%"=="" set FULLHELP= (%HELP%)
+set FULL=[%ADR%] %FULLTEXT%%FULLHELP%
+
+rem echo %NAME%
+
+echo .long %NAME%>>lanchon-stm32-vector.S
+
+echo .weak %NAME%>>lanchon-stm32-isrs.S
+echo .globl %NAME%>>lanchon-stm32-isrs.S
+echo .set %NAME%, __STM32DefaultExceptionHandler>>lanchon-stm32-isrs.S
+
+echo EXTERN (%NAME%)>>lanchon-stm32-names.inc
+
+if %TYPE%==x goto :eof
+
+echo /* %FULL% */>>stm32exceptions.h
+echo void %NAME%(void);>>stm32exceptions.h
+echo.>>stm32exceptions.h
+
+echo /* %FULL% */>>stm32exceptions.c
+echo void %NAME%(void)>>stm32exceptions.c
+echo {>>stm32exceptions.c
+echo DEFAULT_EXCEPTION_HANDLER(%NAME%, "%TEXT%", %NUM%, %ADR%);>>stm32exceptions.c
+echo }>>stm32exceptions.c
+echo.>>stm32exceptions.c
diff --git a/stm32conf/lanchon-stm32/src/exceptions/make.cmd b/stm32conf/lanchon-stm32/src/exceptions/make.cmd new file mode 100644 index 0000000..918ffeb --- /dev/null +++ b/stm32conf/lanchon-stm32/src/exceptions/make.cmd @@ -0,0 +1,76 @@ +@echo off
+setlocal
+
+type lanchon-stm32-vector.S.prolog>lanchon-stm32-vector.S
+type lanchon-stm32-isrs.S.prolog>lanchon-stm32-isrs.S
+type lanchon-stm32-names.inc.prolog>lanchon-stm32-names.inc
+type stm32exceptions.h.prolog>stm32exceptions.h
+type stm32exceptions.c.prolog>stm32exceptions.c
+
+set DO=call make-foreach
+
+rem %DO% 00 - __cs3_stack
+rem %DO% 04 - __cs3_reset
+%DO% 08 e NMIException "NMI" "from the RCC Clock Security System"
+%DO% 0C e HardFaultException "Hard Fault"
+%DO% 10 e MemManageException "Memory Management"
+%DO% 14 e BusFaultException "Bus Fault" "prefetch and memory access faults"
+%DO% 18 e UsageFaultException "Usage Fault" "undefined instruction or illegal state faults"
+%DO% 1C x
+%DO% 20 x
+%DO% 24 x
+%DO% 28 x
+%DO% 2C e SVCHandler "SVCall" "system service call via SWI instruction"
+%DO% 30 e DebugMonitor "Debug Monitor"
+%DO% 34 x
+%DO% 38 e PendSVC "PendSVC" "pendable request for system service"
+%DO% 3C e SysTickHandler "SysTick"
+%DO% 40 i WWDG_IRQHandler "WWDG"
+%DO% 44 i PVD_IRQHandler "PVD" "EXTI Line 16"
+%DO% 48 i TAMPER_IRQHandler "Tamper"
+%DO% 4C i RTC_IRQHandler "RTC"
+%DO% 50 i FLASH_IRQHandler "Flash"
+%DO% 54 i RCC_IRQHandler "RCC"
+%DO% 58 i EXTI0_IRQHandler "EXTI Line 0"
+%DO% 5C i EXTI1_IRQHandler "EXTI Line 1"
+%DO% 60 i EXTI2_IRQHandler "EXTI Line 2"
+%DO% 64 i EXTI3_IRQHandler "EXTI Line 3"
+%DO% 68 i EXTI4_IRQHandler "EXTI Line 4"
+%DO% 6C i DMAChannel1_IRQHandler "DMA Channel 1"
+%DO% 70 i DMAChannel2_IRQHandler "DMA Channel 2"
+%DO% 74 i DMAChannel3_IRQHandler "DMA Channel 3"
+%DO% 78 i DMAChannel4_IRQHandler "DMA Channel 4"
+%DO% 7C i DMAChannel5_IRQHandler "DMA Channel 5"
+%DO% 80 i DMAChannel6_IRQHandler "DMA Channel 6"
+%DO% 84 i DMAChannel7_IRQHandler "DMA Channel 7"
+%DO% 88 i ADC_IRQHandler "ADC"
+%DO% 8C i USB_HP_CAN_TX_IRQHandler "USB High Priority/CAN TX"
+%DO% 90 i USB_LP_CAN_RX0_IRQHandler "USB Low Priority/CAN RX0"
+%DO% 94 i CAN_RX1_IRQHandler "CAN RX1"
+%DO% 98 i CAN_SCE_IRQHandler "CAN SCE"
+%DO% 9C i EXTI9_5_IRQHandler "EXTI Lines 5-9"
+%DO% A0 i TIM1_BRK_IRQHandler "TIM1 Break"
+%DO% A4 i TIM1_UP_IRQHandler "TIM1 Update"
+%DO% A8 i TIM1_TRG_COM_IRQHandler "TIM1 Trigger/Commutation"
+%DO% AC i TIM1_CC_IRQHandler "TIM1 Capture/Compare"
+%DO% B0 i TIM2_IRQHandler "TIM2"
+%DO% B4 i TIM3_IRQHandler "TIM3"
+%DO% B8 i TIM4_IRQHandler "TIM4"
+%DO% BC i I2C1_EV_IRQHandler "I2C1 Event"
+%DO% C0 i I2C1_ER_IRQHandler "I2C1 Error"
+%DO% C4 i I2C2_EV_IRQHandler "I2C2 Event"
+%DO% C8 i I2C2_ER_IRQHandler "I2C2 Error"
+%DO% CC i SPI1_IRQHandler "SPI1"
+%DO% D0 i SPI2_IRQHandler "SPI2"
+%DO% D4 i USART1_IRQHandler "USART1"
+%DO% D8 i USART2_IRQHandler "USART2"
+%DO% DC i USART3_IRQHandler "USART3"
+%DO% E0 i EXTI15_10_IRQHandler "EXTI Lines 10-15"
+%DO% E4 i RTCAlarm_IRQHandler "RTC Alarm" "EXTI Line 17"
+%DO% E8 i USBWakeUp_IRQHandler "USB Wake Up" "EXTI Line 18"
+
+type lanchon-stm32-vector.S.epilog>>lanchon-stm32-vector.S
+type lanchon-stm32-isrs.S.epilog>>lanchon-stm32-isrs.S
+type lanchon-stm32-names.inc.epilog>>lanchon-stm32-names.inc
+type stm32exceptions.h.epilog>>stm32exceptions.h
+type stm32exceptions.c.epilog>>stm32exceptions.c
diff --git a/stm32conf/lanchon-stm32/src/exceptions/stm32exceptions.c.epilog b/stm32conf/lanchon-stm32/src/exceptions/stm32exceptions.c.epilog new file mode 100644 index 0000000..7e500a1 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/exceptions/stm32exceptions.c.epilog @@ -0,0 +1 @@ +#endif /* COMBINED_DEFAULT_HANDLER */
diff --git a/stm32conf/lanchon-stm32/src/exceptions/stm32exceptions.c.prolog b/stm32conf/lanchon-stm32/src/exceptions/stm32exceptions.c.prolog new file mode 100644 index 0000000..140f151 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/exceptions/stm32exceptions.c.prolog @@ -0,0 +1,20 @@ +/* Exception handlers for STM32 (by Lanchon)
+ *
+ * This code is meant to handle exceptions that the application does not expect.
+ * Handlers that are part of the application should be defined elsewhere. */
+
+#include "stm32exceptions.h"
+
+#ifndef CUSTOM_EXCEPTION_HANDLER
+ #ifdef DEBUG
+ /* Use individual infinite loops to ease debugging. */
+ #define DEFAULT_EXCEPTION_HANDLER(handler, name, number, address) while (1);
+ #else
+ /* Avoid individual infinite loops when not debugging. */
+ #define SHARED_EXCEPTION_HANDLER
+ #endif
+#endif
+
+/* Undefined handlers will default to a shared infinite loop (see lanchon-stm32-isrs.S). */
+#ifndef SHARED_EXCEPTION_HANDLER
+
diff --git a/stm32conf/lanchon-stm32/src/exceptions/stm32exceptions.h.epilog b/stm32conf/lanchon-stm32/src/exceptions/stm32exceptions.h.epilog new file mode 100644 index 0000000..6314553 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/exceptions/stm32exceptions.h.epilog @@ -0,0 +1,5 @@ +#if __cplusplus
+}
+#endif
+
+#endif /* __STM32EXCEPTIONS_H */
diff --git a/stm32conf/lanchon-stm32/src/exceptions/stm32exceptions.h.prolog b/stm32conf/lanchon-stm32/src/exceptions/stm32exceptions.h.prolog new file mode 100644 index 0000000..dbf6ce9 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/exceptions/stm32exceptions.h.prolog @@ -0,0 +1,24 @@ +/* Exception handlers for STM32 (by Lanchon) */
+
+#ifndef __STM32EXCEPTIONS_H
+#define __STM32EXCEPTIONS_H
+
+#if __cplusplus
+extern "C"
+{
+#endif
+
+/* Use a shared infinite loop for unexpected exceptions. */
+/* #define SHARED_EXCEPTION_HANDLER */
+
+/* Or use an external handler for unexpected exceptions. */
+/* #define CUSTOM_EXCEPTION_HANDLER */
+
+/* Or else use individual infinite loops when debugging,
+ * or a shared infinite loop when not. */
+
+#ifdef CUSTOM_EXCEPTION_HANDLER
+ void unexpected_exception(const char* name, int address);
+ #define DEFAULT_EXCEPTION_HANDLER(handler, name, number, address) unexpected_exception(name, address);
+#endif
+
diff --git a/stm32conf/lanchon-stm32/src/lanchon-stm32-reset.S b/stm32conf/lanchon-stm32/src/lanchon-stm32-reset.S new file mode 100644 index 0000000..518f99f --- /dev/null +++ b/stm32conf/lanchon-stm32/src/lanchon-stm32-reset.S @@ -0,0 +1,39 @@ +/* Reset code for STM32 (by Lanchon)
+ *
+ * Version:Sourcery G++ 4.2-84
+ * BugURL:https://support.codesourcery.com/GNUToolchain/
+ *
+ * Copyright 2007 CodeSourcery.
+ *
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions. No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply. */
+
+#if defined(__thumb2__) || defined(__ARM_ARCH_6M__)
+#define THUMB 1
+ .thumb
+ .thumb_func
+#else
+ .arm
+#endif
+ .section .cs3.reset,"x",%progbits
+ .globl __cs3_reset_lanchon_stm32
+ .type __cs3_reset_lanchon_stm32, %function
+__cs3_reset_lanchon_stm32:
+ .fnstart
+#if THUMB
+ ldr r0,=_start
+ bx r0
+#else
+ b _start
+#endif
+ .pool
+ .cantunwind
+ .fnend
+ .size __cs3_reset_lanchon_stm32,.-__cs3_reset_lanchon_stm32
diff --git a/stm32conf/lanchon-stm32/src/libcs3-lanchon-stm32/lanchon-stm32-isrs.S b/stm32conf/lanchon-stm32/src/libcs3-lanchon-stm32/lanchon-stm32-isrs.S new file mode 100644 index 0000000..b68af59 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/libcs3-lanchon-stm32/lanchon-stm32-isrs.S @@ -0,0 +1,187 @@ +/* ISRs for STM32 (by Lanchon) */
+
+ .thumb
+
+#if defined (L_lanchon_stm32_isr_interrupt)
+
+ .globl __STM32DefaultExceptionHandler
+ .type __STM32DefaultExceptionHandler, %function
+
+__STM32DefaultExceptionHandler:
+ b .
+
+ .size __STM32DefaultExceptionHandler, . - __STM32DefaultExceptionHandler
+
+ .weak NMIException
+ .globl NMIException
+ .set NMIException, __STM32DefaultExceptionHandler
+ .weak HardFaultException
+ .globl HardFaultException
+ .set HardFaultException, __STM32DefaultExceptionHandler
+ .weak MemManageException
+ .globl MemManageException
+ .set MemManageException, __STM32DefaultExceptionHandler
+ .weak BusFaultException
+ .globl BusFaultException
+ .set BusFaultException, __STM32DefaultExceptionHandler
+ .weak UsageFaultException
+ .globl UsageFaultException
+ .set UsageFaultException, __STM32DefaultExceptionHandler
+ .weak __STM32ReservedException7
+ .globl __STM32ReservedException7
+ .set __STM32ReservedException7, __STM32DefaultExceptionHandler
+ .weak __STM32ReservedException8
+ .globl __STM32ReservedException8
+ .set __STM32ReservedException8, __STM32DefaultExceptionHandler
+ .weak __STM32ReservedException9
+ .globl __STM32ReservedException9
+ .set __STM32ReservedException9, __STM32DefaultExceptionHandler
+ .weak __STM32ReservedException10
+ .globl __STM32ReservedException10
+ .set __STM32ReservedException10, __STM32DefaultExceptionHandler
+ .weak SVCHandler
+ .globl SVCHandler
+ .set SVCHandler, __STM32DefaultExceptionHandler
+ .weak DebugMonitor
+ .globl DebugMonitor
+ .set DebugMonitor, __STM32DefaultExceptionHandler
+ .weak __STM32ReservedException13
+ .globl __STM32ReservedException13
+ .set __STM32ReservedException13, __STM32DefaultExceptionHandler
+ .weak PendSVC
+ .globl PendSVC
+ .set PendSVC, __STM32DefaultExceptionHandler
+ .weak SysTickHandler
+ .globl SysTickHandler
+ .set SysTickHandler, __STM32DefaultExceptionHandler
+ .weak WWDG_IRQHandler
+ .globl WWDG_IRQHandler
+ .set WWDG_IRQHandler, __STM32DefaultExceptionHandler
+ .weak PVD_IRQHandler
+ .globl PVD_IRQHandler
+ .set PVD_IRQHandler, __STM32DefaultExceptionHandler
+ .weak TAMPER_IRQHandler
+ .globl TAMPER_IRQHandler
+ .set TAMPER_IRQHandler, __STM32DefaultExceptionHandler
+ .weak RTC_IRQHandler
+ .globl RTC_IRQHandler
+ .set RTC_IRQHandler, __STM32DefaultExceptionHandler
+ .weak FLASH_IRQHandler
+ .globl FLASH_IRQHandler
+ .set FLASH_IRQHandler, __STM32DefaultExceptionHandler
+ .weak RCC_IRQHandler
+ .globl RCC_IRQHandler
+ .set RCC_IRQHandler, __STM32DefaultExceptionHandler
+ .weak EXTI0_IRQHandler
+ .globl EXTI0_IRQHandler
+ .set EXTI0_IRQHandler, __STM32DefaultExceptionHandler
+ .weak EXTI1_IRQHandler
+ .globl EXTI1_IRQHandler
+ .set EXTI1_IRQHandler, __STM32DefaultExceptionHandler
+ .weak EXTI2_IRQHandler
+ .globl EXTI2_IRQHandler
+ .set EXTI2_IRQHandler, __STM32DefaultExceptionHandler
+ .weak EXTI3_IRQHandler
+ .globl EXTI3_IRQHandler
+ .set EXTI3_IRQHandler, __STM32DefaultExceptionHandler
+ .weak EXTI4_IRQHandler
+ .globl EXTI4_IRQHandler
+ .set EXTI4_IRQHandler, __STM32DefaultExceptionHandler
+ .weak DMAChannel1_IRQHandler
+ .globl DMAChannel1_IRQHandler
+ .set DMAChannel1_IRQHandler, __STM32DefaultExceptionHandler
+ .weak DMAChannel2_IRQHandler
+ .globl DMAChannel2_IRQHandler
+ .set DMAChannel2_IRQHandler, __STM32DefaultExceptionHandler
+ .weak DMAChannel3_IRQHandler
+ .globl DMAChannel3_IRQHandler
+ .set DMAChannel3_IRQHandler, __STM32DefaultExceptionHandler
+ .weak DMAChannel4_IRQHandler
+ .globl DMAChannel4_IRQHandler
+ .set DMAChannel4_IRQHandler, __STM32DefaultExceptionHandler
+ .weak DMAChannel5_IRQHandler
+ .globl DMAChannel5_IRQHandler
+ .set DMAChannel5_IRQHandler, __STM32DefaultExceptionHandler
+ .weak DMAChannel6_IRQHandler
+ .globl DMAChannel6_IRQHandler
+ .set DMAChannel6_IRQHandler, __STM32DefaultExceptionHandler
+ .weak DMAChannel7_IRQHandler
+ .globl DMAChannel7_IRQHandler
+ .set DMAChannel7_IRQHandler, __STM32DefaultExceptionHandler
+ .weak ADC_IRQHandler
+ .globl ADC_IRQHandler
+ .set ADC_IRQHandler, __STM32DefaultExceptionHandler
+ .weak USB_HP_CAN_TX_IRQHandler
+ .globl USB_HP_CAN_TX_IRQHandler
+ .set USB_HP_CAN_TX_IRQHandler, __STM32DefaultExceptionHandler
+ .weak USB_LP_CAN_RX0_IRQHandler
+ .globl USB_LP_CAN_RX0_IRQHandler
+ .set USB_LP_CAN_RX0_IRQHandler, __STM32DefaultExceptionHandler
+ .weak CAN_RX1_IRQHandler
+ .globl CAN_RX1_IRQHandler
+ .set CAN_RX1_IRQHandler, __STM32DefaultExceptionHandler
+ .weak CAN_SCE_IRQHandler
+ .globl CAN_SCE_IRQHandler
+ .set CAN_SCE_IRQHandler, __STM32DefaultExceptionHandler
+ .weak EXTI9_5_IRQHandler
+ .globl EXTI9_5_IRQHandler
+ .set EXTI9_5_IRQHandler, __STM32DefaultExceptionHandler
+ .weak TIM1_BRK_IRQHandler
+ .globl TIM1_BRK_IRQHandler
+ .set TIM1_BRK_IRQHandler, __STM32DefaultExceptionHandler
+ .weak TIM1_UP_IRQHandler
+ .globl TIM1_UP_IRQHandler
+ .set TIM1_UP_IRQHandler, __STM32DefaultExceptionHandler
+ .weak TIM1_TRG_COM_IRQHandler
+ .globl TIM1_TRG_COM_IRQHandler
+ .set TIM1_TRG_COM_IRQHandler, __STM32DefaultExceptionHandler
+ .weak TIM1_CC_IRQHandler
+ .globl TIM1_CC_IRQHandler
+ .set TIM1_CC_IRQHandler, __STM32DefaultExceptionHandler
+ .weak TIM2_IRQHandler
+ .globl TIM2_IRQHandler
+ .set TIM2_IRQHandler, __STM32DefaultExceptionHandler
+ .weak TIM3_IRQHandler
+ .globl TIM3_IRQHandler
+ .set TIM3_IRQHandler, __STM32DefaultExceptionHandler
+ .weak TIM4_IRQHandler
+ .globl TIM4_IRQHandler
+ .set TIM4_IRQHandler, __STM32DefaultExceptionHandler
+ .weak I2C1_EV_IRQHandler
+ .globl I2C1_EV_IRQHandler
+ .set I2C1_EV_IRQHandler, __STM32DefaultExceptionHandler
+ .weak I2C1_ER_IRQHandler
+ .globl I2C1_ER_IRQHandler
+ .set I2C1_ER_IRQHandler, __STM32DefaultExceptionHandler
+ .weak I2C2_EV_IRQHandler
+ .globl I2C2_EV_IRQHandler
+ .set I2C2_EV_IRQHandler, __STM32DefaultExceptionHandler
+ .weak I2C2_ER_IRQHandler
+ .globl I2C2_ER_IRQHandler
+ .set I2C2_ER_IRQHandler, __STM32DefaultExceptionHandler
+ .weak SPI1_IRQHandler
+ .globl SPI1_IRQHandler
+ .set SPI1_IRQHandler, __STM32DefaultExceptionHandler
+ .weak SPI2_IRQHandler
+ .globl SPI2_IRQHandler
+ .set SPI2_IRQHandler, __STM32DefaultExceptionHandler
+ .weak USART1_IRQHandler
+ .globl USART1_IRQHandler
+ .set USART1_IRQHandler, __STM32DefaultExceptionHandler
+ .weak USART2_IRQHandler
+ .globl USART2_IRQHandler
+ .set USART2_IRQHandler, __STM32DefaultExceptionHandler
+ .weak USART3_IRQHandler
+ .globl USART3_IRQHandler
+ .set USART3_IRQHandler, __STM32DefaultExceptionHandler
+ .weak EXTI15_10_IRQHandler
+ .globl EXTI15_10_IRQHandler
+ .set EXTI15_10_IRQHandler, __STM32DefaultExceptionHandler
+ .weak RTCAlarm_IRQHandler
+ .globl RTCAlarm_IRQHandler
+ .set RTCAlarm_IRQHandler, __STM32DefaultExceptionHandler
+ .weak USBWakeUp_IRQHandler
+ .globl USBWakeUp_IRQHandler
+ .set USBWakeUp_IRQHandler, __STM32DefaultExceptionHandler
+
+#endif /* L_lanchon_stm32_isr_interrupt */
diff --git a/stm32conf/lanchon-stm32/src/libcs3-lanchon-stm32/lanchon-stm32-vector.S b/stm32conf/lanchon-stm32/src/libcs3-lanchon-stm32/lanchon-stm32-vector.S new file mode 100644 index 0000000..17a9c01 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/libcs3-lanchon-stm32/lanchon-stm32-vector.S @@ -0,0 +1,69 @@ +/* Vector table for STM32 (by Lanchon) */
+
+ .section ".cs3.interrupt_vector"
+
+ .globl __cs3_interrupt_vector_lanchon_stm32
+ .type __cs3_interrupt_vector_lanchon_stm32, %object
+
+__cs3_interrupt_vector_lanchon_stm32:
+ .long __cs3_stack
+ .long __cs3_reset
+ .long NMIException
+ .long HardFaultException
+ .long MemManageException
+ .long BusFaultException
+ .long UsageFaultException
+ .long __STM32ReservedException7
+ .long __STM32ReservedException8
+ .long __STM32ReservedException9
+ .long __STM32ReservedException10
+ .long SVCHandler
+ .long DebugMonitor
+ .long __STM32ReservedException13
+ .long PendSVC
+ .long SysTickHandler
+ .long WWDG_IRQHandler
+ .long PVD_IRQHandler
+ .long TAMPER_IRQHandler
+ .long RTC_IRQHandler
+ .long FLASH_IRQHandler
+ .long RCC_IRQHandler
+ .long EXTI0_IRQHandler
+ .long EXTI1_IRQHandler
+ .long EXTI2_IRQHandler
+ .long EXTI3_IRQHandler
+ .long EXTI4_IRQHandler
+ .long DMAChannel1_IRQHandler
+ .long DMAChannel2_IRQHandler
+ .long DMAChannel3_IRQHandler
+ .long DMAChannel4_IRQHandler
+ .long DMAChannel5_IRQHandler
+ .long DMAChannel6_IRQHandler
+ .long DMAChannel7_IRQHandler
+ .long ADC_IRQHandler
+ .long USB_HP_CAN_TX_IRQHandler
+ .long USB_LP_CAN_RX0_IRQHandler
+ .long CAN_RX1_IRQHandler
+ .long CAN_SCE_IRQHandler
+ .long EXTI9_5_IRQHandler
+ .long TIM1_BRK_IRQHandler
+ .long TIM1_UP_IRQHandler
+ .long TIM1_TRG_COM_IRQHandler
+ .long TIM1_CC_IRQHandler
+ .long TIM2_IRQHandler
+ .long TIM3_IRQHandler
+ .long TIM4_IRQHandler
+ .long I2C1_EV_IRQHandler
+ .long I2C1_ER_IRQHandler
+ .long I2C2_EV_IRQHandler
+ .long I2C2_ER_IRQHandler
+ .long SPI1_IRQHandler
+ .long SPI2_IRQHandler
+ .long USART1_IRQHandler
+ .long USART2_IRQHandler
+ .long USART3_IRQHandler
+ .long EXTI15_10_IRQHandler
+ .long RTCAlarm_IRQHandler
+ .long USBWakeUp_IRQHandler
+
+ .size __cs3_interrupt_vector_lanchon_stm32, . - __cs3_interrupt_vector_lanchon_stm32
diff --git a/stm32conf/lanchon-stm32/src/libcs3-lanchon-stm32/lanchon_stm32_isr_interrupt.S b/stm32conf/lanchon-stm32/src/libcs3-lanchon-stm32/lanchon_stm32_isr_interrupt.S new file mode 100644 index 0000000..1f6c54a --- /dev/null +++ b/stm32conf/lanchon-stm32/src/libcs3-lanchon-stm32/lanchon_stm32_isr_interrupt.S @@ -0,0 +1,4 @@ +/* ISRs for STM32 (by Lanchon) */
+
+#define L_lanchon_stm32_isr_interrupt 1
+#include "lanchon-stm32-isrs.S"
diff --git a/stm32conf/lanchon-stm32/src/libcs3-lanchon-stm32/makefile b/stm32conf/lanchon-stm32/src/libcs3-lanchon-stm32/makefile new file mode 100644 index 0000000..1c5eac1 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/libcs3-lanchon-stm32/makefile @@ -0,0 +1,36 @@ +# setup environment
+
+TARGET_ARCH = -mcpu=cortex-m3 -mthumb
+
+CC = arm-none-eabi-gcc
+CFLAGS =
+
+AS = $(CC) -x assembler-with-cpp -c $(TARGET_ARCH)
+ASFLAGS =
+
+AR = arm-none-eabi-ar
+ARFLAGS = cr
+
+
+LIB_OUT = libcs3-lanchon-stm32.a
+
+LIB_OBJS = lanchon-stm32-vector.o lanchon_stm32_isr_interrupt.o
+
+
+# all
+
+.PHONY: all
+all: $(LIB_OUT)
+
+
+# lib
+
+$(LIB_OUT): $(LIB_OBJS)
+ $(AR) $(ARFLAGS) $@ $(LIB_OBJS)
+
+
+# clean
+
+.PHONY: clean
+clean:
+ -rm -f $(LIB_OBJS) $(LIB_OUT)
diff --git a/stm32conf/lanchon-stm32/src/libcs3/generic-m-reset.S b/stm32conf/lanchon-stm32/src/libcs3/generic-m-reset.S new file mode 100644 index 0000000..95dbdbe --- /dev/null +++ b/stm32conf/lanchon-stm32/src/libcs3/generic-m-reset.S @@ -0,0 +1,87 @@ +/* Reset code for generic-m
+ *
+ * Version:Sourcery G++ 4.2-84
+ * BugURL:https://support.codesourcery.com/GNUToolchain/
+ *
+ * Copyright 2007 CodeSourcery.
+ *
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions. No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply. */
+
+#if defined(__thumb2__) || defined(__ARM_ARCH_6M__)
+#define THUMB 1
+ .thumb
+ .thumb_func
+#else
+ .arm
+#endif
+ .section .cs3.reset,"x",%progbits
+ .globl __cs3_reset_generic_m
+ .type __cs3_reset_generic_m, %function
+__cs3_reset_generic_m:
+ .fnstart
+#include <rdi-io.h>
+
+ adr r1, __cs3_heap_start_ptr
+ mov r0,#AngelSWI_Reason_HeapInfo
+#if THUMB
+ bkpt 0xAB
+#else
+ swi 0x123456
+#endif
+ cmp r0,#0
+ blt 2f
+/* __cs3_heap_start contains
+ [0] ?
+ [4] zero or heap limit
+ [8] zero or top of stack
+ [12] ? */
+ ldr r2, __cs3_heap_start_ptr
+
+#if THUMB
+ ldr r1,=__cs3_stack
+ mov sp,r1
+#else
+ ldr sp,=__cs3_stack
+#endif
+ ldr r0,[r2,#8] /* top of stack */
+ cmp r0, #0
+#if THUMB
+ beq 1f
+ mov sp,r0
+1:
+#else
+ movne sp,r0
+#endif
+ ldr r1,=__cs3_heap_limit
+ ldr r0,[r2,#4] /* heap limit */
+ cmp r0,#0
+#if THUMB
+ beq 1f
+ str r0,[r1]
+1:
+#else
+ strne r0,[r1]
+#endif
+ .word __cs3_heap_start
+2:
+#if THUMB
+ ldr r0,=__cs3_start_c
+ bx r0
+#else
+ b __cs3_start_c
+#endif
+ .pool
+ .cantunwind
+ .fnend
+ .align 2
+__cs3_heap_start_ptr:
+ .word __cs3_heap_start
+ .size __cs3_reset_generic_m,.-__cs3_reset_generic_m
diff --git a/stm32conf/lanchon-stm32/src/libcs3/generic-reset.S b/stm32conf/lanchon-stm32/src/libcs3/generic-reset.S new file mode 100644 index 0000000..d5b54ab --- /dev/null +++ b/stm32conf/lanchon-stm32/src/libcs3/generic-reset.S @@ -0,0 +1,87 @@ +/* Reset code for generic
+ *
+ * Version:Sourcery G++ 4.2-84
+ * BugURL:https://support.codesourcery.com/GNUToolchain/
+ *
+ * Copyright 2007 CodeSourcery.
+ *
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions. No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply. */
+
+#if defined(__thumb2__) || defined(__ARM_ARCH_6M__)
+#define THUMB 1
+ .thumb
+ .thumb_func
+#else
+ .arm
+#endif
+ .section .cs3.reset,"x",%progbits
+ .globl __cs3_reset_generic
+ .type __cs3_reset_generic, %function
+__cs3_reset_generic:
+ .fnstart
+#include <rdi-io.h>
+
+ adr r1, __cs3_heap_start_ptr
+ mov r0,#AngelSWI_Reason_HeapInfo
+#if THUMB
+ bkpt 0xAB
+#else
+ swi 0x123456
+#endif
+ cmp r0,#0
+ blt 2f
+/* __cs3_heap_start contains
+ [0] ?
+ [4] zero or heap limit
+ [8] zero or top of stack
+ [12] ? */
+ ldr r2, __cs3_heap_start_ptr
+
+#if THUMB
+ ldr r1,=__cs3_stack
+ mov sp,r1
+#else
+ ldr sp,=__cs3_stack
+#endif
+ ldr r0,[r2,#8] /* top of stack */
+ cmp r0, #0
+#if THUMB
+ beq 1f
+ mov sp,r0
+1:
+#else
+ movne sp,r0
+#endif
+ ldr r1,=__cs3_heap_limit
+ ldr r0,[r2,#4] /* heap limit */
+ cmp r0,#0
+#if THUMB
+ beq 1f
+ str r0,[r1]
+1:
+#else
+ strne r0,[r1]
+#endif
+ .word __cs3_heap_start
+2:
+#if THUMB
+ ldr r0,=__cs3_start_c
+ bx r0
+#else
+ b __cs3_start_c
+#endif
+ .pool
+ .cantunwind
+ .fnend
+ .align 2
+__cs3_heap_start_ptr:
+ .word __cs3_heap_start
+ .size __cs3_reset_generic,.-__cs3_reset_generic
diff --git a/stm32conf/lanchon-stm32/src/libcs3/start_c.c b/stm32conf/lanchon-stm32/src/libcs3/start_c.c new file mode 100644 index 0000000..dff9fa3 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/libcs3/start_c.c @@ -0,0 +1,58 @@ +/* CS3 start_c routine.
+ *
+ * Copyright (c) 2006, 2007 CodeSourcery Inc
+ *
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions. No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply.
+ */
+
+#include "cs3.h"
+
+extern void __libc_init_array (void);
+
+extern int main (int, char **, char **);
+
+extern void exit (int) __attribute__ ((noreturn, weak));
+
+void __attribute ((noreturn))
+__cs3_start_c (void)
+{
+ unsigned regions = __cs3_region_num;
+ const struct __cs3_region *rptr = __cs3_regions;
+ int exit_code;
+
+ /* Initialize memory */
+ for (regions = __cs3_region_num, rptr = __cs3_regions; regions--; rptr++)
+ {
+ long long *src = (long long *)rptr->init;
+ long long *dst = (long long *)rptr->data;
+ unsigned limit = rptr->init_size;
+ unsigned count;
+
+ if (src != dst)
+ for (count = 0; count != limit; count += sizeof (long long))
+ *dst++ = *src++;
+ else
+ dst = (long long *)((char *)dst + limit);
+ limit = rptr->zero_size;
+ for (count = 0; count != limit; count += sizeof (long long))
+ *dst++ = 0;
+ }
+
+ /* Run initializers. */
+ __libc_init_array ();
+
+ exit_code = main (0, NULL, NULL);
+ if (exit)
+ exit (exit_code);
+ /* If exit is NULL, make sure we don't return. */
+ for (;;)
+ continue;
+}
diff --git a/stm32conf/lanchon-stm32/src/libcs3arm/arm-isrs.S b/stm32conf/lanchon-stm32/src/libcs3arm/arm-isrs.S new file mode 100644 index 0000000..3688573 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/libcs3arm/arm-isrs.S @@ -0,0 +1,49 @@ +/* ISRs for arm
+ *
+ * Version:Sourcery G++ 4.2-84
+ * BugURL:https://support.codesourcery.com/GNUToolchain/
+ *
+ * Copyright 2007 CodeSourcery.
+ *
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions. No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply. */
+
+ .arch armv4t
+ .arm
+
+#if defined (L_arm_isr_interrupt)
+ .globl __cs3_isr_interrupt
+ .type __cs3_isr_interrupt, %function
+__cs3_isr_interrupt:
+ b .
+ .size __cs3_isr_interrupt, . - __cs3_isr_interrupt
+
+ .weak __cs3_isr_undef
+ .globl __cs3_isr_undef
+ .set __cs3_isr_undef, __cs3_isr_interrupt
+ .weak __cs3_isr_swi
+ .globl __cs3_isr_swi
+ .set __cs3_isr_swi, __cs3_isr_interrupt
+ .weak __cs3_isr_pabort
+ .globl __cs3_isr_pabort
+ .set __cs3_isr_pabort, __cs3_isr_interrupt
+ .weak __cs3_isr_dabort
+ .globl __cs3_isr_dabort
+ .set __cs3_isr_dabort, __cs3_isr_interrupt
+ .weak __cs3_isr_reserved
+ .globl __cs3_isr_reserved
+ .set __cs3_isr_reserved, __cs3_isr_interrupt
+ .weak __cs3_isr_irq
+ .globl __cs3_isr_irq
+ .set __cs3_isr_irq, __cs3_isr_interrupt
+ .weak __cs3_isr_fiq
+ .globl __cs3_isr_fiq
+ .set __cs3_isr_fiq, __cs3_isr_interrupt
+#endif /* interrupt */
diff --git a/stm32conf/lanchon-stm32/src/libcs3arm/arm-vector.S b/stm32conf/lanchon-stm32/src/libcs3arm/arm-vector.S new file mode 100644 index 0000000..1c5b632 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/libcs3arm/arm-vector.S @@ -0,0 +1,40 @@ +/* Vector table for arm
+ *
+ * Version:Sourcery G++ 4.2-84
+ * BugURL:https://support.codesourcery.com/GNUToolchain/
+ *
+ * Copyright 2007 CodeSourcery.
+ *
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions. No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply. */
+
+ .section ".cs3.interrupt_vector"
+ .globl __cs3_interrupt_vector_arm
+ .type __cs3_interrupt_vector_arm, %object
+__cs3_interrupt_vector_arm:
+ .arch armv4
+ .arm
+ ldr pc, [pc, #24] @ reset
+ ldr pc, [pc, #24] @ undef
+ ldr pc, [pc, #24] @ swi
+ ldr pc, [pc, #24] @ pabort
+ ldr pc, [pc, #24] @ dabort
+ ldr pc, [pc, #24] @ reserved
+ ldr pc, [pc, #24] @ irq
+ ldr pc, [pc, #24] @ fiq
+ .long __cs3_reset
+ .long __cs3_isr_undef
+ .long __cs3_isr_swi
+ .long __cs3_isr_pabort
+ .long __cs3_isr_dabort
+ .long __cs3_isr_reserved
+ .long __cs3_isr_irq
+ .long __cs3_isr_fiq
+ .size __cs3_interrupt_vector_arm, . - __cs3_interrupt_vector_arm
diff --git a/stm32conf/lanchon-stm32/src/libcs3micro/micro-isrs.S b/stm32conf/lanchon-stm32/src/libcs3micro/micro-isrs.S new file mode 100644 index 0000000..19787e4 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/libcs3micro/micro-isrs.S @@ -0,0 +1,165 @@ +/* ISRs for micro
+ *
+ * Version:Sourcery G++ 4.2-84
+ * BugURL:https://support.codesourcery.com/GNUToolchain/
+ *
+ * Copyright 2007 CodeSourcery.
+ *
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions. No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply. */
+
+ .thumb
+
+#if defined (L_micro_isr_interrupt)
+ .globl __cs3_isr_interrupt
+ .type __cs3_isr_interrupt, %function
+__cs3_isr_interrupt:
+ b .
+ .size __cs3_isr_interrupt, . - __cs3_isr_interrupt
+
+ .weak __cs3_isr_nmi
+ .globl __cs3_isr_nmi
+ .set __cs3_isr_nmi, __cs3_isr_interrupt
+ .weak __cs3_isr_hard_fault
+ .globl __cs3_isr_hard_fault
+ .set __cs3_isr_hard_fault, __cs3_isr_interrupt
+ .weak __cs3_isr_mpu_fault
+ .globl __cs3_isr_mpu_fault
+ .set __cs3_isr_mpu_fault, __cs3_isr_interrupt
+ .weak __cs3_isr_bus_fault
+ .globl __cs3_isr_bus_fault
+ .set __cs3_isr_bus_fault, __cs3_isr_interrupt
+ .weak __cs3_isr_usage_fault
+ .globl __cs3_isr_usage_fault
+ .set __cs3_isr_usage_fault, __cs3_isr_interrupt
+ .weak __cs3_isr_reserved_7
+ .globl __cs3_isr_reserved_7
+ .set __cs3_isr_reserved_7, __cs3_isr_interrupt
+ .weak __cs3_isr_reserved_8
+ .globl __cs3_isr_reserved_8
+ .set __cs3_isr_reserved_8, __cs3_isr_interrupt
+ .weak __cs3_isr_reserved_9
+ .globl __cs3_isr_reserved_9
+ .set __cs3_isr_reserved_9, __cs3_isr_interrupt
+ .weak __cs3_isr_reserved_10
+ .globl __cs3_isr_reserved_10
+ .set __cs3_isr_reserved_10, __cs3_isr_interrupt
+ .weak __cs3_isr_svcall
+ .globl __cs3_isr_svcall
+ .set __cs3_isr_svcall, __cs3_isr_interrupt
+ .weak __cs3_isr_debug
+ .globl __cs3_isr_debug
+ .set __cs3_isr_debug, __cs3_isr_interrupt
+ .weak __cs3_isr_reserved_13
+ .globl __cs3_isr_reserved_13
+ .set __cs3_isr_reserved_13, __cs3_isr_interrupt
+ .weak __cs3_isr_pendsv
+ .globl __cs3_isr_pendsv
+ .set __cs3_isr_pendsv, __cs3_isr_interrupt
+ .weak __cs3_isr_systick
+ .globl __cs3_isr_systick
+ .set __cs3_isr_systick, __cs3_isr_interrupt
+ .weak __cs3_isr_external_0
+ .globl __cs3_isr_external_0
+ .set __cs3_isr_external_0, __cs3_isr_interrupt
+ .weak __cs3_isr_external_1
+ .globl __cs3_isr_external_1
+ .set __cs3_isr_external_1, __cs3_isr_interrupt
+ .weak __cs3_isr_external_2
+ .globl __cs3_isr_external_2
+ .set __cs3_isr_external_2, __cs3_isr_interrupt
+ .weak __cs3_isr_external_3
+ .globl __cs3_isr_external_3
+ .set __cs3_isr_external_3, __cs3_isr_interrupt
+ .weak __cs3_isr_external_4
+ .globl __cs3_isr_external_4
+ .set __cs3_isr_external_4, __cs3_isr_interrupt
+ .weak __cs3_isr_external_5
+ .globl __cs3_isr_external_5
+ .set __cs3_isr_external_5, __cs3_isr_interrupt
+ .weak __cs3_isr_external_6
+ .globl __cs3_isr_external_6
+ .set __cs3_isr_external_6, __cs3_isr_interrupt
+ .weak __cs3_isr_external_7
+ .globl __cs3_isr_external_7
+ .set __cs3_isr_external_7, __cs3_isr_interrupt
+ .weak __cs3_isr_external_8
+ .globl __cs3_isr_external_8
+ .set __cs3_isr_external_8, __cs3_isr_interrupt
+ .weak __cs3_isr_external_9
+ .globl __cs3_isr_external_9
+ .set __cs3_isr_external_9, __cs3_isr_interrupt
+ .weak __cs3_isr_external_10
+ .globl __cs3_isr_external_10
+ .set __cs3_isr_external_10, __cs3_isr_interrupt
+ .weak __cs3_isr_external_11
+ .globl __cs3_isr_external_11
+ .set __cs3_isr_external_11, __cs3_isr_interrupt
+ .weak __cs3_isr_external_12
+ .globl __cs3_isr_external_12
+ .set __cs3_isr_external_12, __cs3_isr_interrupt
+ .weak __cs3_isr_external_13
+ .globl __cs3_isr_external_13
+ .set __cs3_isr_external_13, __cs3_isr_interrupt
+ .weak __cs3_isr_external_14
+ .globl __cs3_isr_external_14
+ .set __cs3_isr_external_14, __cs3_isr_interrupt
+ .weak __cs3_isr_external_15
+ .globl __cs3_isr_external_15
+ .set __cs3_isr_external_15, __cs3_isr_interrupt
+ .weak __cs3_isr_external_16
+ .globl __cs3_isr_external_16
+ .set __cs3_isr_external_16, __cs3_isr_interrupt
+ .weak __cs3_isr_external_17
+ .globl __cs3_isr_external_17
+ .set __cs3_isr_external_17, __cs3_isr_interrupt
+ .weak __cs3_isr_external_18
+ .globl __cs3_isr_external_18
+ .set __cs3_isr_external_18, __cs3_isr_interrupt
+ .weak __cs3_isr_external_19
+ .globl __cs3_isr_external_19
+ .set __cs3_isr_external_19, __cs3_isr_interrupt
+ .weak __cs3_isr_external_20
+ .globl __cs3_isr_external_20
+ .set __cs3_isr_external_20, __cs3_isr_interrupt
+ .weak __cs3_isr_external_21
+ .globl __cs3_isr_external_21
+ .set __cs3_isr_external_21, __cs3_isr_interrupt
+ .weak __cs3_isr_external_22
+ .globl __cs3_isr_external_22
+ .set __cs3_isr_external_22, __cs3_isr_interrupt
+ .weak __cs3_isr_external_23
+ .globl __cs3_isr_external_23
+ .set __cs3_isr_external_23, __cs3_isr_interrupt
+ .weak __cs3_isr_external_24
+ .globl __cs3_isr_external_24
+ .set __cs3_isr_external_24, __cs3_isr_interrupt
+ .weak __cs3_isr_external_25
+ .globl __cs3_isr_external_25
+ .set __cs3_isr_external_25, __cs3_isr_interrupt
+ .weak __cs3_isr_external_26
+ .globl __cs3_isr_external_26
+ .set __cs3_isr_external_26, __cs3_isr_interrupt
+ .weak __cs3_isr_external_27
+ .globl __cs3_isr_external_27
+ .set __cs3_isr_external_27, __cs3_isr_interrupt
+ .weak __cs3_isr_external_28
+ .globl __cs3_isr_external_28
+ .set __cs3_isr_external_28, __cs3_isr_interrupt
+ .weak __cs3_isr_external_29
+ .globl __cs3_isr_external_29
+ .set __cs3_isr_external_29, __cs3_isr_interrupt
+ .weak __cs3_isr_external_30
+ .globl __cs3_isr_external_30
+ .set __cs3_isr_external_30, __cs3_isr_interrupt
+ .weak __cs3_isr_external_31
+ .globl __cs3_isr_external_31
+ .set __cs3_isr_external_31, __cs3_isr_interrupt
+#endif /* interrupt */
diff --git a/stm32conf/lanchon-stm32/src/libcs3micro/micro-vector.S b/stm32conf/lanchon-stm32/src/libcs3micro/micro-vector.S new file mode 100644 index 0000000..d00ee17 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/libcs3micro/micro-vector.S @@ -0,0 +1,70 @@ +/* Vector table for micro
+ *
+ * Version:Sourcery G++ 4.2-84
+ * BugURL:https://support.codesourcery.com/GNUToolchain/
+ *
+ * Copyright 2007 CodeSourcery.
+ *
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions. No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply. */
+
+ .section ".cs3.interrupt_vector"
+ .globl __cs3_interrupt_vector_micro
+ .type __cs3_interrupt_vector_micro, %object
+__cs3_interrupt_vector_micro:
+ .long __cs3_stack
+ .long __cs3_reset
+ .long __cs3_isr_nmi
+ .long __cs3_isr_hard_fault
+ .long __cs3_isr_mpu_fault
+ .long __cs3_isr_bus_fault
+ .long __cs3_isr_usage_fault
+ .long __cs3_isr_reserved_7
+ .long __cs3_isr_reserved_8
+ .long __cs3_isr_reserved_9
+ .long __cs3_isr_reserved_10
+ .long __cs3_isr_svcall
+ .long __cs3_isr_debug
+ .long __cs3_isr_reserved_13
+ .long __cs3_isr_pendsv
+ .long __cs3_isr_systick
+ .long __cs3_isr_external_0
+ .long __cs3_isr_external_1
+ .long __cs3_isr_external_2
+ .long __cs3_isr_external_3
+ .long __cs3_isr_external_4
+ .long __cs3_isr_external_5
+ .long __cs3_isr_external_6
+ .long __cs3_isr_external_7
+ .long __cs3_isr_external_8
+ .long __cs3_isr_external_9
+ .long __cs3_isr_external_10
+ .long __cs3_isr_external_11
+ .long __cs3_isr_external_12
+ .long __cs3_isr_external_13
+ .long __cs3_isr_external_14
+ .long __cs3_isr_external_15
+ .long __cs3_isr_external_16
+ .long __cs3_isr_external_17
+ .long __cs3_isr_external_18
+ .long __cs3_isr_external_19
+ .long __cs3_isr_external_20
+ .long __cs3_isr_external_21
+ .long __cs3_isr_external_22
+ .long __cs3_isr_external_23
+ .long __cs3_isr_external_24
+ .long __cs3_isr_external_25
+ .long __cs3_isr_external_26
+ .long __cs3_isr_external_27
+ .long __cs3_isr_external_28
+ .long __cs3_isr_external_29
+ .long __cs3_isr_external_30
+ .long __cs3_isr_external_31
+ .size __cs3_interrupt_vector_micro, . - __cs3_interrupt_vector_micro
diff --git a/stm32conf/lanchon-stm32/src/start.S b/stm32conf/lanchon-stm32/src/start.S new file mode 100644 index 0000000..595af07 --- /dev/null +++ b/stm32conf/lanchon-stm32/src/start.S @@ -0,0 +1,36 @@ +/*
+ * The authors hereby grant permission to use, copy, modify, distribute,
+ * and license this software and its documentation for any purpose, provided
+ * that existing copyright notices are retained in all copies and that this
+ * notice is included verbatim in any distributions. No written agreement,
+ * license, or royalty fee is required for any of the authorized uses.
+ * Modifications to this software may be copyrighted by their authors
+ * and need not follow the licensing terms described here, provided that
+ * the new terms are clearly indicated on the first page of each file where
+ * they apply.
+ */
+
+ .text
+#if defined(__thumb2__) || defined(__ARM_ARCH_6M__)
+#define THUMB 1
+ .code 16
+ .thumb_func
+#else
+ .code 32
+#endif
+ .globl _start
+ .type _start, %function
+_start:
+ .fnstart
+#if THUMB
+ ldr r1,=__cs3_stack
+ mov sp,r1
+ ldr r1,=__cs3_start_c
+ bx r1
+#else
+ ldr sp,=__cs3_stack
+ b __cs3_start_c
+#endif
+ .pool
+ .cantunwind
+ .fnend
diff --git a/stm32conf/run.cfg b/stm32conf/run.cfg new file mode 100644 index 0000000..234a3c8 --- /dev/null +++ b/stm32conf/run.cfg @@ -0,0 +1,75 @@ +# script for stm32 + +interface ft2232 +ft2232_device_desc "Olimex OpenOCD JTAG" +ft2232_layout olimex-jtag +ft2232_vid_pid 0x15ba 0x0003 + +if { [info exists CHIPNAME] } { + set _CHIPNAME $CHIPNAME +} else { + set _CHIPNAME stm32 +} + +if { [info exists ENDIAN] } { + set _ENDIAN $ENDIAN +} else { + set _ENDIAN little +} + +# jtag speed speed should be <= F_CPU/6. F_CPU after reset is 8MHz, so ufse F_JTAG = 1MHz +jtag_khz 1000 + +jtag_nsrst_delay 100 +jtag_ntrst_delay 100 + +#use combined on interfaces or targets that can't set TRST/SRST separately +reset_config trst_and_srst + +#jtag scan chain +if { [info exists CPUTAPID ] } { + set _CPUTAPID $CPUTAPID +} else { + # See STM Document RM0008 + # Section 26.6.3 + set _CPUTAPID 0x3ba00477 +} + +jtag newtap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID + +if { [info exists BSTAPID ] } { + # FIXME this never gets used to override defaults... + set _BSTAPID $BSTAPID +} else { + # See STM Document RM0008 + # Section 29.6.2 + # Low density devices, Rev A + set _BSTAPID1 0x06412041 + # Medium density devices, Rev A + set _BSTAPID2 0x06410041 + # Medium density devices, Rev B and Rev Z + set _BSTAPID3 0x16410041 + # High density devices, Rev A + set _BSTAPID4 0x06414041 + # Connectivity line devices, Rev A and Rev Z + set _BSTAPID5 0x06418041 +} +jtag newtap $_CHIPNAME bs -irlen 5 -expected-id $_BSTAPID1 \ + -expected-id $_BSTAPID2 -expected-id $_BSTAPID3 \ + -expected-id $_BSTAPID4 -expected-id $_BSTAPID5 + + +set _TARGETNAME $_CHIPNAME.cpu +target create $_TARGETNAME cortex_m3 -endian $_ENDIAN -chain-position $_TARGETNAME + +$_TARGETNAME configure -work-area-virt 0 -work-area-phys 0x20000000 -work-area-size 0x5000 -work-area-backup 0 + +flash bank stm32x 0x08000000 0x00020000 0 0 $_TARGETNAME + +proc nopforever {} { + puts "Resetting the chip..." + reset run +} + +init +nopforever |